ExportCloudsDialog.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include "rtabmap/gui/ExportCloudsDialog.h"
00029 #include "ui_exportCloudsDialog.h"
00030 
00031 #include "rtabmap/gui/CloudViewer.h"
00032 #include "rtabmap/gui/TexturingState.h"
00033 #include "rtabmap/utilite/ULogger.h"
00034 #include "rtabmap/utilite/UConversion.h"
00035 #include "rtabmap/utilite/UThread.h"
00036 #include "rtabmap/utilite/UStl.h"
00037 #include "rtabmap/utilite/UMath.h"
00038 
00039 #include "rtabmap/core/util3d_filtering.h"
00040 #include "rtabmap/core/util3d_surface.h"
00041 #include "rtabmap/core/util3d_transforms.h"
00042 #include "rtabmap/core/util3d.h"
00043 #include "rtabmap/core/util2d.h"
00044 #include "rtabmap/core/Graph.h"
00045 #include "rtabmap/core/GainCompensator.h"
00046 #include "rtabmap/core/clams/discrete_depth_distortion_model.h"
00047 #include "rtabmap/core/DBDriver.h"
00048 #include "rtabmap/core/Version.h"
00049 
00050 #include <pcl/conversions.h>
00051 #include <pcl/io/pcd_io.h>
00052 #include <pcl/io/ply_io.h>
00053 #include <pcl/io/vtk_io.h>
00054 #include <pcl/io/obj_io.h>
00055 #include <pcl/pcl_config.h>
00056 #include <pcl/surface/poisson.h>
00057 #include <pcl/common/common.h>
00058 
00059 #include <QPushButton>
00060 #include <QDir>
00061 #include <QFileInfo>
00062 #include <QMessageBox>
00063 #include <QFileDialog>
00064 #include <QInputDialog>
00065 #include <QDesktopWidget>
00066 
00067 #ifdef RTABMAP_CPUTSDF
00068 #include <cpu_tsdf/tsdf_volume_octree.h>
00069 #include <cpu_tsdf/marching_cubes_tsdf_octree.h>
00070 #endif
00071 
00072 #ifdef RTABMAP_OPENCHISEL
00073 #include "chisel_conversions.h"
00074 #include <open_chisel/ProjectionIntegrator.h>
00075 #include <open_chisel/truncation/QuadraticTruncator.h>
00076 #include <open_chisel/weighting/ConstantWeighter.h>
00077 #endif
00078 
00079 namespace rtabmap {
00080 
00081 ExportCloudsDialog::ExportCloudsDialog(QWidget *parent) :
00082         QDialog(parent),
00083         _canceled(false),
00084         _compensator(0),
00085         _dbDriver(0)
00086 {
00087         _ui = new Ui_ExportCloudsDialog();
00088         _ui->setupUi(this);
00089 
00090         connect(_ui->buttonBox->button(QDialogButtonBox::RestoreDefaults), SIGNAL(clicked()), this, SLOT(restoreDefaults()));
00091         QPushButton * loadSettingsButton = _ui->buttonBox->addButton("Load Settings", QDialogButtonBox::ActionRole);
00092         QPushButton * saveSettingsButton = _ui->buttonBox->addButton("Save Settings", QDialogButtonBox::ActionRole);
00093         connect(loadSettingsButton, SIGNAL(clicked()), this, SLOT(loadSettings()));
00094         connect(saveSettingsButton, SIGNAL(clicked()), this, SLOT(saveSettings()));
00095 
00096         restoreDefaults();
00097         _ui->comboBox_upsamplingMethod->setItemData(1, 0, Qt::UserRole - 1); // disable DISTINCT_CLOUD
00098 
00099         connect(_ui->checkBox_fromDepth, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00100         connect(_ui->checkBox_fromDepth, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00101         connect(_ui->checkBox_binary, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00102         connect(_ui->spinBox_normalKSearch, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00103         connect(_ui->doubleSpinBox_normalRadiusSearch, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00104         connect(_ui->comboBox_pipeline, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
00105         connect(_ui->comboBox_pipeline, SIGNAL(currentIndexChanged(int)), this, SLOT(updateReconstructionFlavor()));
00106         connect(_ui->comboBox_meshingApproach, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
00107         connect(_ui->comboBox_meshingApproach, SIGNAL(currentIndexChanged(int)), this, SLOT(updateReconstructionFlavor()));
00108 
00109         connect(_ui->checkBox_regenerate, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00110         connect(_ui->checkBox_regenerate, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00111         connect(_ui->spinBox_decimation, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00112         connect(_ui->doubleSpinBox_maxDepth, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00113         connect(_ui->doubleSpinBox_minDepth, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00114         connect(_ui->spinBox_fillDepthHoles, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00115         connect(_ui->spinBox_fillDepthHolesError, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00116         connect(_ui->lineEdit_roiRatios, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
00117         connect(_ui->lineEdit_distortionModel, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
00118         connect(_ui->toolButton_distortionModel, SIGNAL(clicked()), this, SLOT(selectDistortionModel()));
00119 
00120         connect(_ui->checkBox_bilateral, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00121         connect(_ui->checkBox_bilateral, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00122         connect(_ui->doubleSpinBox_bilateral_sigmaS, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00123         connect(_ui->doubleSpinBox_bilateral_sigmaR, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00124 
00125         connect(_ui->checkBox_filtering, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00126         connect(_ui->checkBox_filtering, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00127         connect(_ui->doubleSpinBox_filteringRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00128         connect(_ui->spinBox_filteringMinNeighbors, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00129 
00130         connect(_ui->checkBox_assemble, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
00131         connect(_ui->checkBox_assemble, SIGNAL(clicked(bool)), this, SLOT(updateReconstructionFlavor()));
00132         connect(_ui->doubleSpinBox_voxelSize_assembled, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00133         connect(_ui->comboBox_frame, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
00134         connect(_ui->comboBox_frame, SIGNAL(currentIndexChanged(int)), this, SLOT(updateReconstructionFlavor()));
00135 
00136         connect(_ui->checkBox_subtraction, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00137         connect(_ui->checkBox_subtraction, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00138         connect(_ui->doubleSpinBox_subtractPointFilteringRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00139         connect(_ui->doubleSpinBox_subtractPointFilteringAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00140         connect(_ui->spinBox_subtractFilteringMinPts, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00141 
00142         connect(_ui->checkBox_smoothing, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00143         connect(_ui->checkBox_smoothing, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00144         connect(_ui->doubleSpinBox_mlsRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00145         connect(_ui->spinBox_polygonialOrder, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00146         connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
00147         connect(_ui->doubleSpinBox_sampleStep, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00148         connect(_ui->spinBox_randomPoints, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00149         connect(_ui->doubleSpinBox_dilationVoxelSize, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00150         connect(_ui->spinBox_dilationSteps, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00151         connect(_ui->doubleSpinBox_mls_outputVoxelSize, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00152         _ui->stackedWidget_upsampling->setCurrentIndex(_ui->comboBox_upsamplingMethod->currentIndex());
00153         connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_upsampling, SLOT(setCurrentIndex(int)));
00154         connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), this, SLOT(updateMLSGrpVisibility()));
00155 
00156         connect(_ui->checkBox_gainCompensation, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00157         connect(_ui->checkBox_gainCompensation, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00158         connect(_ui->doubleSpinBox_gainRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00159         connect(_ui->doubleSpinBox_gainOverlap, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00160         connect(_ui->doubleSpinBox_gainBeta, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00161         connect(_ui->checkBox_gainRGB, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00162         connect(_ui->checkBox_gainFull, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00163         connect(_ui->spinBox_textureBrightnessContrastRatioLow, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00164         connect(_ui->spinBox_textureBrightnessContrastRatioHigh, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00165         connect(_ui->checkBox_exposureFusion, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00166         connect(_ui->checkBox_blending, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00167         connect(_ui->comboBox_blendingDecimation, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
00168 
00169         connect(_ui->checkBox_meshing, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00170         connect(_ui->checkBox_meshing, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00171         connect(_ui->checkBox_meshing, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00172         connect(_ui->doubleSpinBox_gp3Radius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00173         connect(_ui->doubleSpinBox_gp3Mu, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00174         connect(_ui->doubleSpinBox_meshDecimationFactor, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00175         connect(_ui->doubleSpinBox_meshDecimationFactor, SIGNAL(valueChanged(double)), this, SLOT(updateReconstructionFlavor()));
00176         connect(_ui->spinBox_meshMaxPolygons, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00177         connect(_ui->spinBox_meshMaxPolygons, SIGNAL(valueChanged(int)), this, SLOT(updateReconstructionFlavor()));
00178         connect(_ui->doubleSpinBox_transferColorRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00179         connect(_ui->checkBox_cleanMesh, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00180         connect(_ui->spinBox_mesh_minClusterSize, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00181         connect(_ui->checkBox_textureMapping, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00182         connect(_ui->checkBox_textureMapping, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00183         connect(_ui->comboBox_meshingTextureFormat, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
00184         connect(_ui->comboBox_meshingTextureSize, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
00185         connect(_ui->spinBox_mesh_maxTextures, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00186         connect(_ui->doubleSpinBox_meshingTextureMaxDistance, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00187         connect(_ui->doubleSpinBox_meshingTextureMaxDepthError, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00188         connect(_ui->doubleSpinBox_meshingTextureMaxAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00189         connect(_ui->spinBox_mesh_minTextureClusterSize, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00190         connect(_ui->lineEdit_meshingTextureRoiRatios, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
00191         connect(_ui->checkBox_cameraFilter, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00192         connect(_ui->checkBox_cameraFilter, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
00193         connect(_ui->doubleSpinBox_cameraFilterRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00194         connect(_ui->doubleSpinBox_cameraFilterAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00195         connect(_ui->doubleSpinBox_cameraFilterVel, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00196         connect(_ui->doubleSpinBox_cameraFilterVelRad, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00197         connect(_ui->doubleSpinBox_laplacianVariance, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00198 
00199         connect(_ui->checkBox_poisson_outputPolygons, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00200         connect(_ui->checkBox_poisson_manifold, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00201         connect(_ui->spinBox_poisson_depth, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00202         connect(_ui->spinBox_poisson_iso, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00203         connect(_ui->spinBox_poisson_solver, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00204         connect(_ui->spinBox_poisson_minDepth, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00205         connect(_ui->doubleSpinBox_poisson_samples, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00206         connect(_ui->doubleSpinBox_poisson_pointWeight, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00207         connect(_ui->doubleSpinBox_poisson_scale, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00208 
00209         connect(_ui->doubleSpinBox_cputsdf_size, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00210         connect(_ui->doubleSpinBox_cputsdf_resolution, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00211         connect(_ui->doubleSpinBox_cputsdf_tuncPos, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00212         connect(_ui->doubleSpinBox_cputsdf_tuncNeg, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00213         connect(_ui->doubleSpinBox_cputsdf_minWeight, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00214         connect(_ui->doubleSpinBox_cputsdf_flattenRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00215         connect(_ui->spinBox_cputsdf_randomSplit, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00216 
00217         connect(_ui->checkBox_openchisel_mergeVertices, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00218         connect(_ui->spinBox_openchisel_chunk_size_x, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00219         connect(_ui->spinBox_openchisel_chunk_size_y, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00220         connect(_ui->spinBox_openchisel_chunk_size_z, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00221         connect(_ui->doubleSpinBox_openchisel_truncation_constant, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00222         connect(_ui->doubleSpinBox_openchisel_truncation_linear, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00223         connect(_ui->doubleSpinBox_openchisel_truncation_quadratic, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00224         connect(_ui->doubleSpinBox_openchisel_truncation_scale, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00225         connect(_ui->spinBox_openchisel_integration_weight, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00226         connect(_ui->checkBox_openchisel_use_voxel_carving, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00227         connect(_ui->doubleSpinBox_openchisel_carving_dist_m, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00228         connect(_ui->doubleSpinBox_openchisel_near_plane_dist, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00229         connect(_ui->doubleSpinBox_openchisel_far_plane_dist, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00230 
00231 
00232         _progressDialog = new ProgressDialog(this);
00233         _progressDialog->setVisible(false);
00234         _progressDialog->setAutoClose(true, 2);
00235         _progressDialog->setMinimumWidth(600);
00236         _progressDialog->setCancelButtonVisible(true);
00237         connect(_progressDialog, SIGNAL(canceled()), this, SLOT(cancel()));
00238 
00239 #ifdef DISABLE_VTK
00240         _ui->doubleSpinBox_meshDecimationFactor->setEnabled(false);
00241         _ui->spinBox_meshMaxPolygons->setEnabled(false);
00242         _ui->label_meshDecimation->setEnabled(false);
00243         _ui->label_meshMaxPolygons->setEnabled(false);
00244 #endif
00245 
00246 #if CV_MAJOR_VERSION < 3
00247         _ui->checkBox_exposureFusion->setEnabled(false);
00248         _ui->checkBox_exposureFusion->setChecked(false);
00249         _ui->label_exposureFusion->setEnabled(false);
00250 #endif
00251 }
00252 
00253 ExportCloudsDialog::~ExportCloudsDialog()
00254 {
00255         delete _ui;
00256         delete _compensator;
00257 }
00258 
00259 void ExportCloudsDialog::updateMLSGrpVisibility()
00260 {
00261         _ui->groupBox->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 0);
00262         _ui->groupBox_2->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 1);
00263         _ui->groupBox_3->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 2);
00264         _ui->groupBox_4->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 3);
00265         _ui->groupBox_5->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 4);
00266 }
00267 
00268 void ExportCloudsDialog::cancel()
00269 {
00270         _canceled = true;
00271         _progressDialog->appendText(tr("Canceled!"));
00272 }
00273 
00274 void ExportCloudsDialog::forceAssembling(bool enabled)
00275 {
00276         if(enabled)
00277         {
00278                 _ui->checkBox_assemble->setChecked(true);
00279                 _ui->checkBox_assemble->setEnabled(false);
00280         }
00281         else
00282         {
00283                 _ui->checkBox_assemble->setEnabled(true);
00284         }
00285 }
00286 
00287 void ExportCloudsDialog::setProgressDialogToMax()
00288 {
00289         _progressDialog->setValue(_progressDialog->maximumSteps());
00290 }
00291 
00292 void ExportCloudsDialog::saveSettings(QSettings & settings, const QString & group) const
00293 {
00294         if(!group.isEmpty())
00295         {
00296                 settings.beginGroup(group);
00297         }
00298         settings.setValue("pipeline", _ui->comboBox_pipeline->currentIndex());
00299         settings.setValue("from_depth", _ui->checkBox_fromDepth->isChecked());
00300         settings.setValue("binary", _ui->checkBox_binary->isChecked());
00301         settings.setValue("normals_k", _ui->spinBox_normalKSearch->value());
00302         settings.setValue("normals_radius", _ui->doubleSpinBox_normalRadiusSearch->value());
00303 
00304         settings.setValue("regenerate", _ui->checkBox_regenerate->isChecked());
00305         settings.setValue("regenerate_decimation", _ui->spinBox_decimation->value());
00306         settings.setValue("regenerate_max_depth", _ui->doubleSpinBox_maxDepth->value());
00307         settings.setValue("regenerate_min_depth", _ui->doubleSpinBox_minDepth->value());
00308         settings.setValue("regenerate_fill_size", _ui->spinBox_fillDepthHoles->value());
00309         settings.setValue("regenerate_fill_error", _ui->spinBox_fillDepthHolesError->value());
00310         settings.setValue("regenerate_roi", _ui->lineEdit_roiRatios->text());
00311         settings.setValue("regenerate_distortion_model", _ui->lineEdit_distortionModel->text());
00312 
00313         settings.setValue("bilateral", _ui->checkBox_bilateral->isChecked());
00314         settings.setValue("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value());
00315         settings.setValue("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value());
00316 
00317         settings.setValue("filtering", _ui->checkBox_filtering->isChecked());
00318         settings.setValue("filtering_radius", _ui->doubleSpinBox_filteringRadius->value());
00319         settings.setValue("filtering_min_neighbors", _ui->spinBox_filteringMinNeighbors->value());
00320 
00321         settings.setValue("assemble", _ui->checkBox_assemble->isChecked());
00322         settings.setValue("assemble_voxel",_ui->doubleSpinBox_voxelSize_assembled->value());
00323         settings.setValue("frame",_ui->comboBox_frame->currentIndex());
00324 
00325         settings.setValue("subtract",_ui->checkBox_subtraction->isChecked());
00326         settings.setValue("subtract_point_radius",_ui->doubleSpinBox_subtractPointFilteringRadius->value());
00327         settings.setValue("subtract_point_angle",_ui->doubleSpinBox_subtractPointFilteringAngle->value());
00328         settings.setValue("subtract_min_neighbors",_ui->spinBox_subtractFilteringMinPts->value());
00329 
00330         settings.setValue("mls", _ui->checkBox_smoothing->isChecked());
00331         settings.setValue("mls_radius", _ui->doubleSpinBox_mlsRadius->value());
00332         settings.setValue("mls_polygonial_order", _ui->spinBox_polygonialOrder->value());
00333         settings.setValue("mls_upsampling_method", _ui->comboBox_upsamplingMethod->currentIndex());
00334         settings.setValue("mls_upsampling_radius", _ui->doubleSpinBox_sampleRadius->value());
00335         settings.setValue("mls_upsampling_step", _ui->doubleSpinBox_sampleStep->value());
00336         settings.setValue("mls_point_density", _ui->spinBox_randomPoints->value());
00337         settings.setValue("mls_dilation_voxel_size", _ui->doubleSpinBox_dilationVoxelSize->value());
00338         settings.setValue("mls_dilation_iterations", _ui->spinBox_dilationSteps->value());
00339         settings.setValue("mls_output_voxel_size", _ui->doubleSpinBox_mls_outputVoxelSize->value());
00340 
00341         settings.setValue("gain", _ui->checkBox_gainCompensation->isChecked());
00342         settings.setValue("gain_radius", _ui->doubleSpinBox_gainRadius->value());
00343         settings.setValue("gain_overlap", _ui->doubleSpinBox_gainOverlap->value());
00344         settings.setValue("gain_beta", _ui->doubleSpinBox_gainBeta->value());
00345         settings.setValue("gain_rgb", _ui->checkBox_gainRGB->isChecked());
00346         settings.setValue("gain_full", _ui->checkBox_gainFull->isChecked());
00347 
00348         settings.setValue("mesh", _ui->checkBox_meshing->isChecked());
00349         settings.setValue("mesh_radius", _ui->doubleSpinBox_gp3Radius->value());
00350         settings.setValue("mesh_mu", _ui->doubleSpinBox_gp3Mu->value());
00351         settings.setValue("mesh_decimation_factor", _ui->doubleSpinBox_meshDecimationFactor->value());
00352         settings.setValue("mesh_max_polygons", _ui->spinBox_meshMaxPolygons->value());
00353         settings.setValue("mesh_color_radius", _ui->doubleSpinBox_transferColorRadius->value());
00354         settings.setValue("mesh_clean", _ui->checkBox_cleanMesh->isChecked());
00355         settings.setValue("mesh_min_cluster_size", _ui->spinBox_mesh_minClusterSize->value());
00356 
00357         settings.setValue("mesh_dense_strategy", _ui->comboBox_meshingApproach->currentIndex());
00358 
00359         settings.setValue("mesh_texture", _ui->checkBox_textureMapping->isChecked());
00360         settings.setValue("mesh_textureFormat", _ui->comboBox_meshingTextureFormat->currentIndex());
00361         settings.setValue("mesh_textureSize", _ui->comboBox_meshingTextureSize->currentIndex());
00362         settings.setValue("mesh_textureMaxCount", _ui->spinBox_mesh_maxTextures->value());
00363         settings.setValue("mesh_textureMaxDistance", _ui->doubleSpinBox_meshingTextureMaxDistance->value());
00364         settings.setValue("mesh_textureMaxDepthError", _ui->doubleSpinBox_meshingTextureMaxDepthError->value());
00365         settings.setValue("mesh_textureMaxAngle", _ui->doubleSpinBox_meshingTextureMaxAngle->value());
00366         settings.setValue("mesh_textureMinCluster", _ui->spinBox_mesh_minTextureClusterSize->value());
00367         settings.setValue("mesh_textureRoiRatios", _ui->lineEdit_meshingTextureRoiRatios->text());
00368         settings.setValue("mesh_textureCameraFiltering", _ui->checkBox_cameraFilter->isChecked());
00369         settings.setValue("mesh_textureCameraFilteringRadius", _ui->doubleSpinBox_cameraFilterRadius->value());
00370         settings.setValue("mesh_textureCameraFilteringAngle", _ui->doubleSpinBox_cameraFilterAngle->value());
00371         settings.setValue("mesh_textureCameraFilteringVel", _ui->doubleSpinBox_cameraFilterVel->value());
00372         settings.setValue("mesh_textureCameraFilteringVelRad", _ui->doubleSpinBox_cameraFilterVelRad->value());
00373         settings.setValue("mesh_textureCameraFilteringLaplacian", _ui->doubleSpinBox_laplacianVariance->value());
00374         settings.setValue("mesh_textureBrightnessConstrastRatioLow", _ui->spinBox_textureBrightnessContrastRatioLow->value());
00375         settings.setValue("mesh_textureBrightnessConstrastRatioHigh", _ui->spinBox_textureBrightnessContrastRatioHigh->value());
00376         settings.setValue("mesh_textureExposureFusion", _ui->checkBox_exposureFusion->isChecked());
00377         settings.setValue("mesh_textureBlending", _ui->checkBox_blending->isChecked());
00378         settings.setValue("mesh_textureBlendingDecimation", _ui->comboBox_blendingDecimation->currentIndex());
00379 
00380 
00381         settings.setValue("mesh_angle_tolerance", _ui->doubleSpinBox_mesh_angleTolerance->value());
00382         settings.setValue("mesh_quad", _ui->checkBox_mesh_quad->isChecked());
00383         settings.setValue("mesh_triangle_size", _ui->spinBox_mesh_triangleSize->value());
00384 
00385         settings.setValue("poisson_outputPolygons", _ui->checkBox_poisson_outputPolygons->isChecked());
00386         settings.setValue("poisson_manifold", _ui->checkBox_poisson_manifold->isChecked());
00387         settings.setValue("poisson_depth", _ui->spinBox_poisson_depth->value());
00388         settings.setValue("poisson_iso", _ui->spinBox_poisson_iso->value());
00389         settings.setValue("poisson_solver", _ui->spinBox_poisson_solver->value());
00390         settings.setValue("poisson_minDepth", _ui->spinBox_poisson_minDepth->value());
00391         settings.setValue("poisson_samples", _ui->doubleSpinBox_poisson_samples->value());
00392         settings.setValue("poisson_pointWeight", _ui->doubleSpinBox_poisson_pointWeight->value());
00393         settings.setValue("poisson_scale", _ui->doubleSpinBox_poisson_scale->value());
00394 
00395         settings.setValue("cputsdf_size", _ui->doubleSpinBox_cputsdf_size->value());
00396         settings.setValue("cputsdf_resolution", _ui->doubleSpinBox_cputsdf_resolution->value());
00397         settings.setValue("cputsdf_truncPos", _ui->doubleSpinBox_cputsdf_tuncPos->value());
00398         settings.setValue("cputsdf_truncNeg", _ui->doubleSpinBox_cputsdf_tuncNeg->value());
00399         settings.setValue("cputsdf_minWeight", _ui->doubleSpinBox_cputsdf_minWeight->value());
00400         settings.setValue("cputsdf_flattenRadius", _ui->doubleSpinBox_cputsdf_flattenRadius->value());
00401         settings.setValue("cputsdf_randomSplit", _ui->spinBox_cputsdf_randomSplit->value());
00402 
00403         settings.setValue("openchisel_merge_vertices", _ui->checkBox_openchisel_mergeVertices->isChecked());
00404         settings.setValue("openchisel_chunk_size_x", _ui->spinBox_openchisel_chunk_size_x->value());
00405         settings.setValue("openchisel_chunk_size_y", _ui->spinBox_openchisel_chunk_size_y->value());
00406         settings.setValue("openchisel_chunk_size_z", _ui->spinBox_openchisel_chunk_size_z->value());
00407         settings.setValue("openchisel_truncation_constant", _ui->doubleSpinBox_openchisel_truncation_constant->value());
00408         settings.setValue("openchisel_truncation_linear", _ui->doubleSpinBox_openchisel_truncation_linear->value());
00409         settings.setValue("openchisel_truncation_quadratic", _ui->doubleSpinBox_openchisel_truncation_quadratic->value());
00410         settings.setValue("openchisel_truncation_scale", _ui->doubleSpinBox_openchisel_truncation_scale->value());
00411         settings.setValue("openchisel_integration_weight", _ui->spinBox_openchisel_integration_weight->value());
00412         settings.setValue("openchisel_use_voxel_carving", _ui->checkBox_openchisel_use_voxel_carving->isChecked());
00413         settings.setValue("openchisel_carving_dist_m", _ui->doubleSpinBox_openchisel_carving_dist_m->value());
00414         settings.setValue("openchisel_near_plane_dist", _ui->doubleSpinBox_openchisel_near_plane_dist->value());
00415         settings.setValue("openchisel_far_plane_dist", _ui->doubleSpinBox_openchisel_far_plane_dist->value());
00416 
00417         if(!group.isEmpty())
00418         {
00419                 settings.endGroup();
00420         }
00421 }
00422 
00423 void ExportCloudsDialog::loadSettings(QSettings & settings, const QString & group)
00424 {
00425         if(!group.isEmpty())
00426         {
00427                 settings.beginGroup(group);
00428         }
00429 
00430         _ui->comboBox_pipeline->setCurrentIndex(settings.value("pipeline", _ui->comboBox_pipeline->currentIndex()).toInt());
00431         _ui->checkBox_fromDepth->setChecked(settings.value("from_depth", _ui->checkBox_fromDepth->isChecked()).toBool());
00432         _ui->checkBox_binary->setChecked(settings.value("binary", _ui->checkBox_binary->isChecked()).toBool());
00433         _ui->spinBox_normalKSearch->setValue(settings.value("normals_k", _ui->spinBox_normalKSearch->value()).toInt());
00434         _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value("normals_radius", _ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
00435 
00436         _ui->checkBox_regenerate->setChecked(settings.value("regenerate", _ui->checkBox_regenerate->isChecked()).toBool());
00437         _ui->spinBox_decimation->setValue(settings.value("regenerate_decimation", _ui->spinBox_decimation->value()).toInt());
00438         _ui->doubleSpinBox_maxDepth->setValue(settings.value("regenerate_max_depth", _ui->doubleSpinBox_maxDepth->value()).toDouble());
00439         _ui->doubleSpinBox_minDepth->setValue(settings.value("regenerate_min_depth", _ui->doubleSpinBox_minDepth->value()).toDouble());
00440         _ui->spinBox_fillDepthHoles->setValue(settings.value("regenerate_fill_size", _ui->spinBox_fillDepthHoles->value()).toInt());
00441         _ui->spinBox_fillDepthHolesError->setValue(settings.value("regenerate_fill_error", _ui->spinBox_fillDepthHolesError->value()).toInt());
00442         _ui->lineEdit_roiRatios->setText(settings.value("regenerate_roi", _ui->lineEdit_roiRatios->text()).toString());
00443         _ui->lineEdit_distortionModel->setText(settings.value("regenerate_distortion_model", _ui->lineEdit_distortionModel->text()).toString());
00444 
00445         _ui->checkBox_bilateral->setChecked(settings.value("bilateral", _ui->checkBox_bilateral->isChecked()).toBool());
00446         _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
00447         _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
00448 
00449         _ui->checkBox_filtering->setChecked(settings.value("filtering", _ui->checkBox_filtering->isChecked()).toBool());
00450         _ui->doubleSpinBox_filteringRadius->setValue(settings.value("filtering_radius", _ui->doubleSpinBox_filteringRadius->value()).toDouble());
00451         _ui->spinBox_filteringMinNeighbors->setValue(settings.value("filtering_min_neighbors", _ui->spinBox_filteringMinNeighbors->value()).toInt());
00452 
00453         if(_ui->checkBox_assemble->isEnabled())
00454         {
00455                 _ui->checkBox_assemble->setChecked(settings.value("assemble", _ui->checkBox_assemble->isChecked()).toBool());
00456         }
00457         _ui->doubleSpinBox_voxelSize_assembled->setValue(settings.value("assemble_voxel", _ui->doubleSpinBox_voxelSize_assembled->value()).toDouble());
00458         _ui->comboBox_frame->setCurrentIndex(settings.value("frame", _ui->comboBox_frame->currentIndex()).toInt());
00459 
00460         _ui->checkBox_subtraction->setChecked(settings.value("subtract",_ui->checkBox_subtraction->isChecked()).toBool());
00461         _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(settings.value("subtract_point_radius",_ui->doubleSpinBox_subtractPointFilteringRadius->value()).toDouble());
00462         _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(settings.value("subtract_point_angle",_ui->doubleSpinBox_subtractPointFilteringAngle->value()).toDouble());
00463         _ui->spinBox_subtractFilteringMinPts->setValue(settings.value("subtract_min_neighbors",_ui->spinBox_subtractFilteringMinPts->value()).toInt());
00464 
00465         _ui->checkBox_smoothing->setChecked(settings.value("mls", _ui->checkBox_smoothing->isChecked()).toBool());
00466         _ui->doubleSpinBox_mlsRadius->setValue(settings.value("mls_radius", _ui->doubleSpinBox_mlsRadius->value()).toDouble());
00467         _ui->spinBox_polygonialOrder->setValue(settings.value("mls_polygonial_order", _ui->spinBox_polygonialOrder->value()).toInt());
00468         _ui->comboBox_upsamplingMethod->setCurrentIndex(settings.value("mls_upsampling_method", _ui->comboBox_upsamplingMethod->currentIndex()).toInt());
00469         _ui->doubleSpinBox_sampleRadius->setValue(settings.value("mls_upsampling_radius", _ui->doubleSpinBox_sampleRadius->value()).toDouble());
00470         _ui->doubleSpinBox_sampleStep->setValue(settings.value("mls_upsampling_step", _ui->doubleSpinBox_sampleStep->value()).toDouble());
00471         _ui->spinBox_randomPoints->setValue(settings.value("mls_point_density", _ui->spinBox_randomPoints->value()).toInt());
00472         _ui->doubleSpinBox_dilationVoxelSize->setValue(settings.value("mls_dilation_voxel_size", _ui->doubleSpinBox_dilationVoxelSize->value()).toDouble());
00473         _ui->spinBox_dilationSteps->setValue(settings.value("mls_dilation_iterations", _ui->spinBox_dilationSteps->value()).toInt());
00474         _ui->doubleSpinBox_mls_outputVoxelSize->setValue(settings.value("mls_output_voxel_size", _ui->doubleSpinBox_mls_outputVoxelSize->value()).toInt());
00475 
00476         _ui->checkBox_gainCompensation->setChecked(settings.value("gain", _ui->checkBox_gainCompensation->isChecked()).toBool());
00477         _ui->doubleSpinBox_gainRadius->setValue(settings.value("gain_radius", _ui->doubleSpinBox_gainRadius->value()).toDouble());
00478         _ui->doubleSpinBox_gainOverlap->setValue(settings.value("gain_overlap", _ui->doubleSpinBox_gainOverlap->value()).toDouble());
00479         _ui->doubleSpinBox_gainBeta->setValue(settings.value("gain_beta", _ui->doubleSpinBox_gainBeta->value()).toDouble());
00480         _ui->checkBox_gainRGB->setChecked(settings.value("gain_rgb", _ui->checkBox_gainRGB->isChecked()).toBool());
00481         _ui->checkBox_gainFull->setChecked(settings.value("gain_full", _ui->checkBox_gainFull->isChecked()).toBool());
00482 
00483         _ui->checkBox_meshing->setChecked(settings.value("mesh", _ui->checkBox_meshing->isChecked()).toBool());
00484         _ui->doubleSpinBox_gp3Radius->setValue(settings.value("mesh_radius", _ui->doubleSpinBox_gp3Radius->value()).toDouble());
00485         _ui->doubleSpinBox_gp3Mu->setValue(settings.value("mesh_mu", _ui->doubleSpinBox_gp3Mu->value()).toDouble());
00486         _ui->doubleSpinBox_meshDecimationFactor->setValue(settings.value("mesh_decimation_factor",_ui->doubleSpinBox_meshDecimationFactor->value()).toDouble());
00487         _ui->spinBox_meshMaxPolygons->setValue(settings.value("mesh_max_polygons",_ui->spinBox_meshMaxPolygons->value()).toDouble());
00488         _ui->doubleSpinBox_transferColorRadius->setValue(settings.value("mesh_color_radius",_ui->doubleSpinBox_transferColorRadius->value()).toDouble());
00489         _ui->checkBox_cleanMesh->setChecked(settings.value("mesh_clean",_ui->checkBox_cleanMesh->isChecked()).toBool());
00490         _ui->spinBox_mesh_minClusterSize->setValue(settings.value("mesh_min_cluster_size", _ui->spinBox_mesh_minClusterSize->value()).toInt());
00491 
00492         _ui->comboBox_meshingApproach->setCurrentIndex(settings.value("mesh_dense_strategy", _ui->comboBox_meshingApproach->currentIndex()).toInt());
00493 
00494         _ui->checkBox_textureMapping->setChecked(settings.value("mesh_texture", _ui->checkBox_textureMapping->isChecked()).toBool());
00495         _ui->comboBox_meshingTextureFormat->setCurrentIndex(settings.value("mesh_textureFormat", _ui->comboBox_meshingTextureFormat->currentIndex()).toInt());
00496         _ui->comboBox_meshingTextureSize->setCurrentIndex(settings.value("mesh_textureSize", _ui->comboBox_meshingTextureSize->currentIndex()).toInt());
00497         _ui->spinBox_mesh_maxTextures->setValue(settings.value("mesh_textureMaxCount", _ui->spinBox_mesh_maxTextures->value()).toInt());
00498         _ui->doubleSpinBox_meshingTextureMaxDistance->setValue(settings.value("mesh_textureMaxDistance", _ui->doubleSpinBox_meshingTextureMaxDistance->value()).toDouble());
00499         _ui->doubleSpinBox_meshingTextureMaxDepthError->setValue(settings.value("mesh_textureMaxDepthError", _ui->doubleSpinBox_meshingTextureMaxDepthError->value()).toDouble());
00500         _ui->doubleSpinBox_meshingTextureMaxAngle->setValue(settings.value("mesh_textureMaxAngle", _ui->doubleSpinBox_meshingTextureMaxAngle->value()).toDouble());
00501         _ui->spinBox_mesh_minTextureClusterSize->setValue(settings.value("mesh_textureMinCluster", _ui->spinBox_mesh_minTextureClusterSize->value()).toDouble());
00502         _ui->lineEdit_meshingTextureRoiRatios->setText(settings.value("mesh_textureRoiRatios", _ui->lineEdit_meshingTextureRoiRatios->text()).toString());
00503         _ui->checkBox_cameraFilter->setChecked(settings.value("mesh_textureCameraFiltering", _ui->checkBox_cameraFilter->isChecked()).toBool());
00504         _ui->doubleSpinBox_cameraFilterRadius->setValue(settings.value("mesh_textureCameraFilteringRadius", _ui->doubleSpinBox_cameraFilterRadius->value()).toDouble());
00505         _ui->doubleSpinBox_cameraFilterAngle->setValue(settings.value("mesh_textureCameraFilteringAngle", _ui->doubleSpinBox_cameraFilterAngle->value()).toDouble());
00506         _ui->doubleSpinBox_cameraFilterVel->setValue(settings.value("mesh_textureCameraFilteringVel", _ui->doubleSpinBox_cameraFilterVel->value()).toDouble());
00507         _ui->doubleSpinBox_cameraFilterVelRad->setValue(settings.value("mesh_textureCameraFilteringVelRad", _ui->doubleSpinBox_cameraFilterVelRad->value()).toDouble());
00508         _ui->doubleSpinBox_laplacianVariance->setValue(settings.value("mesh_textureCameraFilteringLaplacian", _ui->doubleSpinBox_laplacianVariance->value()).toDouble());
00509         _ui->spinBox_textureBrightnessContrastRatioLow->setValue(settings.value("mesh_textureBrightnessConstrastRatioLow", _ui->spinBox_textureBrightnessContrastRatioLow->value()).toDouble());
00510         _ui->spinBox_textureBrightnessContrastRatioHigh->setValue(settings.value("mesh_textureBrightnessConstrastRatioHigh", _ui->spinBox_textureBrightnessContrastRatioHigh->value()).toDouble());
00511         if(_ui->checkBox_exposureFusion->isEnabled())
00512         {
00513                 _ui->checkBox_exposureFusion->setChecked(settings.value("mesh_textureExposureFusion", _ui->checkBox_exposureFusion->isChecked()).toBool());
00514         }
00515         _ui->checkBox_blending->setChecked(settings.value("mesh_textureBlending", _ui->checkBox_blending->isChecked()).toBool());
00516         _ui->comboBox_blendingDecimation->setCurrentIndex(settings.value("mesh_textureBlendingDecimation", _ui->comboBox_blendingDecimation->currentIndex()).toInt());
00517 
00518         _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value("mesh_angle_tolerance", _ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
00519         _ui->checkBox_mesh_quad->setChecked(settings.value("mesh_quad", _ui->checkBox_mesh_quad->isChecked()).toBool());
00520         _ui->spinBox_mesh_triangleSize->setValue(settings.value("mesh_triangle_size", _ui->spinBox_mesh_triangleSize->value()).toInt());
00521 
00522         _ui->checkBox_poisson_outputPolygons->setChecked(settings.value("poisson_outputPolygons", _ui->checkBox_poisson_outputPolygons->isChecked()).toBool());
00523         _ui->checkBox_poisson_manifold->setChecked(settings.value("poisson_manifold", _ui->checkBox_poisson_manifold->isChecked()).toBool());
00524         _ui->spinBox_poisson_depth->setValue(settings.value("poisson_depth", _ui->spinBox_poisson_depth->value()).toInt());
00525         _ui->spinBox_poisson_iso->setValue(settings.value("poisson_iso", _ui->spinBox_poisson_iso->value()).toInt());
00526         _ui->spinBox_poisson_solver->setValue(settings.value("poisson_solver", _ui->spinBox_poisson_solver->value()).toInt());
00527         _ui->spinBox_poisson_minDepth->setValue(settings.value("poisson_minDepth", _ui->spinBox_poisson_minDepth->value()).toInt());
00528         _ui->doubleSpinBox_poisson_samples->setValue(settings.value("poisson_samples", _ui->doubleSpinBox_poisson_samples->value()).toDouble());
00529         _ui->doubleSpinBox_poisson_pointWeight->setValue(settings.value("poisson_pointWeight", _ui->doubleSpinBox_poisson_pointWeight->value()).toDouble());
00530         _ui->doubleSpinBox_poisson_scale->setValue(settings.value("poisson_scale", _ui->doubleSpinBox_poisson_scale->value()).toDouble());
00531 
00532         _ui->doubleSpinBox_cputsdf_size->setValue(settings.value("cputsdf_size", _ui->doubleSpinBox_cputsdf_size->value()).toDouble());
00533         _ui->doubleSpinBox_cputsdf_resolution->setValue(settings.value("cputsdf_resolution", _ui->doubleSpinBox_cputsdf_resolution->value()).toDouble());
00534         _ui->doubleSpinBox_cputsdf_tuncPos->setValue(settings.value("cputsdf_truncPos", _ui->doubleSpinBox_cputsdf_tuncPos->value()).toDouble());
00535         _ui->doubleSpinBox_cputsdf_tuncNeg->setValue(settings.value("cputsdf_truncNeg", _ui->doubleSpinBox_cputsdf_tuncNeg->value()).toDouble());
00536         _ui->doubleSpinBox_cputsdf_minWeight->setValue(settings.value("cputsdf_minWeight", _ui->doubleSpinBox_cputsdf_minWeight->value()).toDouble());
00537         _ui->doubleSpinBox_cputsdf_flattenRadius->setValue(settings.value("cputsdf_flattenRadius", _ui->doubleSpinBox_cputsdf_flattenRadius->value()).toDouble());
00538         _ui->spinBox_cputsdf_randomSplit->setValue(settings.value("cputsdf_randomSplit", _ui->spinBox_cputsdf_randomSplit->value()).toInt());
00539 
00540         _ui->checkBox_openchisel_mergeVertices->setChecked(settings.value("openchisel_merge_vertices", _ui->checkBox_openchisel_mergeVertices->isChecked()).toBool());
00541         _ui->spinBox_openchisel_chunk_size_x->setValue(settings.value("openchisel_chunk_size_x", _ui->spinBox_openchisel_chunk_size_x->value()).toInt());
00542         _ui->spinBox_openchisel_chunk_size_y->setValue(settings.value("openchisel_chunk_size_y", _ui->spinBox_openchisel_chunk_size_y->value()).toInt());
00543         _ui->spinBox_openchisel_chunk_size_z->setValue(settings.value("openchisel_chunk_size_z", _ui->spinBox_openchisel_chunk_size_z->value()).toInt());
00544         _ui->doubleSpinBox_openchisel_truncation_constant->setValue(settings.value("openchisel_truncation_constant", _ui->doubleSpinBox_openchisel_truncation_constant->value()).toDouble());
00545         _ui->doubleSpinBox_openchisel_truncation_linear->setValue(settings.value("openchisel_truncation_linear", _ui->doubleSpinBox_openchisel_truncation_linear->value()).toDouble());
00546         _ui->doubleSpinBox_openchisel_truncation_quadratic->setValue(settings.value("openchisel_truncation_quadratic", _ui->doubleSpinBox_openchisel_truncation_quadratic->value()).toDouble());
00547         _ui->doubleSpinBox_openchisel_truncation_scale->setValue(settings.value("openchisel_truncation_scale", _ui->doubleSpinBox_openchisel_truncation_scale->value()).toDouble());
00548         _ui->spinBox_openchisel_integration_weight->setValue(settings.value("openchisel_integration_weight", _ui->spinBox_openchisel_integration_weight->value()).toInt());
00549         _ui->checkBox_openchisel_use_voxel_carving->setChecked(settings.value("openchisel_use_voxel_carving", _ui->checkBox_openchisel_use_voxel_carving->isChecked()).toBool());
00550         _ui->doubleSpinBox_openchisel_carving_dist_m->setValue(settings.value("openchisel_carving_dist_m", _ui->doubleSpinBox_openchisel_carving_dist_m->value()).toDouble());
00551         _ui->doubleSpinBox_openchisel_near_plane_dist->setValue(settings.value("openchisel_near_plane_dist", _ui->doubleSpinBox_openchisel_near_plane_dist->value()).toDouble());
00552         _ui->doubleSpinBox_openchisel_far_plane_dist->setValue(settings.value("openchisel_far_plane_dist", _ui->doubleSpinBox_openchisel_far_plane_dist->value()).toDouble());
00553 
00554         updateReconstructionFlavor();
00555         updateMLSGrpVisibility();
00556 
00557         if(!group.isEmpty())
00558         {
00559                 settings.endGroup();
00560         }
00561 }
00562 
00563 void ExportCloudsDialog::restoreDefaults()
00564 {
00565         _ui->comboBox_pipeline->setCurrentIndex(1);
00566         _ui->checkBox_fromDepth->setChecked(true);
00567         _ui->checkBox_binary->setChecked(true);
00568         _ui->spinBox_normalKSearch->setValue(20);
00569         _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
00570 
00571         _ui->checkBox_regenerate->setChecked(_dbDriver!=0?true:false);
00572         _ui->spinBox_decimation->setValue(1);
00573         _ui->doubleSpinBox_maxDepth->setValue(4);
00574         _ui->doubleSpinBox_minDepth->setValue(0);
00575         _ui->spinBox_fillDepthHoles->setValue(0);
00576         _ui->spinBox_fillDepthHolesError->setValue(2);
00577         _ui->lineEdit_roiRatios->setText("0.0 0.0 0.0 0.0");
00578         _ui->lineEdit_distortionModel->setText("");
00579 
00580         _ui->checkBox_bilateral->setChecked(false);
00581         _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
00582         _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
00583 
00584         _ui->checkBox_filtering->setChecked(false);
00585         _ui->doubleSpinBox_filteringRadius->setValue(0.02);
00586         _ui->spinBox_filteringMinNeighbors->setValue(2);
00587 
00588         _ui->checkBox_assemble->setChecked(true);
00589         _ui->doubleSpinBox_voxelSize_assembled->setValue(0.01);
00590         _ui->comboBox_frame->setCurrentIndex(0);
00591 
00592         _ui->checkBox_subtraction->setChecked(false);
00593         _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(0.02);
00594         _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(0);
00595         _ui->spinBox_subtractFilteringMinPts->setValue(5);
00596 
00597         _ui->checkBox_smoothing->setChecked(false);
00598         _ui->doubleSpinBox_mlsRadius->setValue(0.04);
00599         _ui->spinBox_polygonialOrder->setValue(2);
00600         _ui->comboBox_upsamplingMethod->setCurrentIndex(0);
00601         _ui->doubleSpinBox_sampleRadius->setValue(0.01);
00602         _ui->doubleSpinBox_sampleStep->setValue(0.005);
00603         _ui->spinBox_randomPoints->setValue(10);
00604         _ui->doubleSpinBox_dilationVoxelSize->setValue(0.005);
00605         _ui->spinBox_dilationSteps->setValue(1);
00606         _ui->doubleSpinBox_mls_outputVoxelSize->setValue(0);
00607 
00608         _ui->checkBox_gainCompensation->setChecked(false);
00609         _ui->doubleSpinBox_gainRadius->setValue(0.02);
00610         _ui->doubleSpinBox_gainOverlap->setValue(0.0);
00611         _ui->doubleSpinBox_gainBeta->setValue(10);
00612         _ui->checkBox_gainRGB->setChecked(true);
00613         _ui->checkBox_gainFull->setChecked(false);
00614 
00615         _ui->checkBox_meshing->setChecked(false);
00616         _ui->doubleSpinBox_gp3Radius->setValue(0.2);
00617         _ui->doubleSpinBox_gp3Mu->setValue(2.5);
00618         _ui->doubleSpinBox_meshDecimationFactor->setValue(0.0);
00619         _ui->spinBox_meshMaxPolygons->setValue(0);
00620         _ui->doubleSpinBox_transferColorRadius->setValue(0.025);
00621         _ui->checkBox_cleanMesh->setChecked(true);
00622         _ui->spinBox_mesh_minClusterSize->setValue(0);
00623 
00624         _ui->comboBox_meshingApproach->setCurrentIndex(1);
00625 
00626         _ui->checkBox_textureMapping->setChecked(false);
00627         _ui->comboBox_meshingTextureFormat->setCurrentIndex(0);
00628         _ui->comboBox_meshingTextureSize->setCurrentIndex(5); // 4096
00629         _ui->spinBox_mesh_maxTextures->setValue(1);
00630         _ui->doubleSpinBox_meshingTextureMaxDistance->setValue(3.0);
00631         _ui->doubleSpinBox_meshingTextureMaxDepthError->setValue(0.0);
00632         _ui->doubleSpinBox_meshingTextureMaxAngle->setValue(0.0);
00633         _ui->spinBox_mesh_minTextureClusterSize->setValue(50);
00634         _ui->lineEdit_meshingTextureRoiRatios->setText("0.0 0.0 0.0 0.0");
00635         _ui->checkBox_cameraFilter->setChecked(false);
00636         _ui->doubleSpinBox_cameraFilterRadius->setValue(0);
00637         _ui->doubleSpinBox_cameraFilterAngle->setValue(30);
00638         _ui->doubleSpinBox_cameraFilterVel->setValue(0);
00639         _ui->doubleSpinBox_cameraFilterVelRad->setValue(0);
00640         _ui->doubleSpinBox_laplacianVariance->setValue(0);
00641         _ui->spinBox_textureBrightnessContrastRatioLow->setValue(0);
00642         _ui->spinBox_textureBrightnessContrastRatioHigh->setValue(0);
00643         _ui->checkBox_exposureFusion->setChecked(false);
00644         _ui->checkBox_blending->setChecked(true);
00645         _ui->comboBox_blendingDecimation->setCurrentIndex(0);
00646 
00647         _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
00648         _ui->checkBox_mesh_quad->setChecked(false);
00649         _ui->spinBox_mesh_triangleSize->setValue(1);
00650 
00651         _ui->checkBox_poisson_outputPolygons->setChecked(false);
00652         _ui->checkBox_poisson_manifold->setChecked(true);
00653         _ui->spinBox_poisson_depth->setValue(0);
00654         _ui->spinBox_poisson_iso->setValue(8);
00655         _ui->spinBox_poisson_solver->setValue(8);
00656         _ui->spinBox_poisson_minDepth->setValue(5);
00657         _ui->doubleSpinBox_poisson_samples->setValue(1.0);
00658         _ui->doubleSpinBox_poisson_pointWeight->setValue(4.0);
00659         _ui->doubleSpinBox_poisson_scale->setValue(1.1);
00660 
00661         _ui->doubleSpinBox_cputsdf_size->setValue(12.0);
00662         _ui->doubleSpinBox_cputsdf_resolution->setValue(0.01);
00663         _ui->doubleSpinBox_cputsdf_tuncPos->setValue(0.03);
00664         _ui->doubleSpinBox_cputsdf_tuncNeg->setValue(0.03);
00665         _ui->doubleSpinBox_cputsdf_minWeight->setValue(0);
00666         _ui->doubleSpinBox_cputsdf_flattenRadius->setValue(0.005);
00667         _ui->spinBox_cputsdf_randomSplit->setValue(1);
00668 
00669         _ui->checkBox_openchisel_mergeVertices->setChecked(true);
00670         _ui->spinBox_openchisel_chunk_size_x->setValue(16);
00671         _ui->spinBox_openchisel_chunk_size_y->setValue(16);
00672         _ui->spinBox_openchisel_chunk_size_z->setValue(16);
00673         _ui->doubleSpinBox_openchisel_truncation_constant->setValue(0.001504);
00674         _ui->doubleSpinBox_openchisel_truncation_linear->setValue(0.00152);
00675         _ui->doubleSpinBox_openchisel_truncation_quadratic->setValue(0.0019);
00676         _ui->doubleSpinBox_openchisel_truncation_scale->setValue(10.0);
00677         _ui->spinBox_openchisel_integration_weight->setValue(1);
00678         _ui->checkBox_openchisel_use_voxel_carving->setChecked(false);
00679         _ui->doubleSpinBox_openchisel_carving_dist_m->setValue(0.05);
00680         _ui->doubleSpinBox_openchisel_near_plane_dist->setValue(0.05);
00681         _ui->doubleSpinBox_openchisel_far_plane_dist->setValue(1.1);
00682 
00683 
00684         updateReconstructionFlavor();
00685         updateMLSGrpVisibility();
00686 
00687         this->update();
00688 }
00689 
00690 void ExportCloudsDialog::loadSettings()
00691 {
00692         QString path = QFileDialog::getOpenFileName(this, tr("Load Settings"), _workingDirectory, tr("Config (*.ini)"));
00693         if(path.size())
00694         {
00695                 QSettings settings(path, QSettings::IniFormat);
00696                 settings.beginGroup("Gui");
00697                 settings.beginGroup(this->objectName());
00698                 this->loadSettings(settings);
00699                 settings.endGroup(); // "name"
00700                 settings.endGroup(); // Gui
00701         }
00702 }
00703 
00704 void ExportCloudsDialog::saveSettings()
00705 {
00706         QString path = QFileDialog::getSaveFileName(this, tr("Save Settings"), _workingDirectory, tr("Config (*.ini)"));
00707         if(path.size())
00708         {
00709                 QSettings settings(path, QSettings::IniFormat);
00710                 settings.beginGroup("Gui");
00711                 settings.beginGroup(this->objectName());
00712                 this->saveSettings(settings);
00713                 settings.endGroup(); // "name"
00714                 settings.endGroup(); // Gui
00715         }
00716 }
00717 
00718 void ExportCloudsDialog::updateReconstructionFlavor()
00719 {
00720         if(!_ui->checkBox_fromDepth->isChecked())
00721         {
00722                 _ui->comboBox_pipeline->setCurrentIndex(1);
00723                 _ui->comboBox_pipeline->setEnabled(false);
00724                 _ui->comboBox_frame->setItemData(2, 0,Qt::UserRole - 1);
00725                 _ui->comboBox_frame->setItemData(3, 1|32,Qt::UserRole - 1);
00726                 if(_ui->comboBox_frame->currentIndex() == 2)
00727                 {
00728                         _ui->comboBox_frame->setCurrentIndex(0);
00729                 }
00730         }
00731         else
00732         {
00733                 _ui->comboBox_pipeline->setEnabled(true);
00734                 _ui->comboBox_frame->setItemData(2, 1|32,Qt::UserRole - 1);
00735                 _ui->comboBox_frame->setItemData(3, 0,Qt::UserRole - 1);
00736                 if(_ui->comboBox_frame->currentIndex() == 3)
00737                 {
00738                         _ui->comboBox_frame->setCurrentIndex(0);
00739                 }
00740         }
00741 
00742         _ui->checkBox_smoothing->setVisible(_ui->comboBox_pipeline->currentIndex() == 1);
00743         _ui->checkBox_smoothing->setEnabled(_ui->comboBox_pipeline->currentIndex() == 1);
00744         _ui->label_smoothing->setVisible(_ui->comboBox_pipeline->currentIndex() == 1);
00745 
00746         _ui->comboBox_frame->setEnabled(!_ui->checkBox_assemble->isChecked() && _ui->checkBox_binary->isEnabled());
00747         _ui->comboBox_frame->setVisible(_ui->comboBox_frame->isEnabled());
00748         _ui->label_frame->setVisible(_ui->comboBox_frame->isEnabled());
00749         _ui->checkBox_gainCompensation->setEnabled(!(_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex() == 2));
00750         _ui->checkBox_gainCompensation->setVisible(_ui->checkBox_gainCompensation->isEnabled());
00751         _ui->label_gainCompensation->setVisible(_ui->checkBox_gainCompensation->isEnabled());
00752 
00753         _ui->groupBox_regenerate->setVisible(_ui->checkBox_regenerate->isChecked() && _ui->checkBox_fromDepth->isChecked());
00754         _ui->groupBox_regenerateScans->setVisible(_ui->checkBox_regenerate->isChecked() && !_ui->checkBox_fromDepth->isChecked());
00755         _ui->groupBox_bilateral->setVisible(_ui->checkBox_bilateral->isChecked());
00756         _ui->groupBox_filtering->setVisible(_ui->checkBox_filtering->isChecked());
00757         _ui->groupBox_gain->setVisible(_ui->checkBox_gainCompensation->isEnabled() && _ui->checkBox_gainCompensation->isChecked());
00758         _ui->groupBox_mls->setVisible(_ui->checkBox_smoothing->isEnabled() && _ui->checkBox_smoothing->isChecked());
00759         _ui->groupBox_meshing->setVisible(_ui->checkBox_meshing->isChecked());
00760         _ui->groupBox_subtraction->setVisible(_ui->checkBox_subtraction->isChecked());
00761         _ui->groupBox_textureMapping->setVisible(_ui->checkBox_textureMapping->isChecked());
00762         _ui->groupBox_cameraFilter->setVisible(_ui->checkBox_cameraFilter->isChecked());
00763 
00764         // dense texturing options
00765         if(_ui->checkBox_meshing->isChecked())
00766         {
00767                 //GP3
00768                 _ui->comboBox_meshingApproach->setItemData(0, _ui->comboBox_pipeline->currentIndex() == 1?1 | 32:0,Qt::UserRole - 1);
00769 
00770                 //Poisson
00771                 _ui->comboBox_meshingApproach->setItemData(1, _ui->comboBox_pipeline->currentIndex() == 1 && _ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
00772 
00773                 //CPU-TSDF
00774 #ifdef RTABMAP_CPUTSDF
00775                 _ui->comboBox_meshingApproach->setItemData(2, _ui->comboBox_pipeline->currentIndex() == 0 && _ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
00776 #else
00777                 _ui->comboBox_meshingApproach->setItemData(2, 0, Qt::UserRole - 1);
00778 #endif
00779 
00780                 // Organized
00781                 _ui->comboBox_meshingApproach->setItemData(3, _ui->comboBox_pipeline->currentIndex() == 0?1 | 32:0,Qt::UserRole - 1);
00782 
00783                 //Open Chisel
00784 #ifdef RTABMAP_OPENCHISEL
00785                 _ui->comboBox_meshingApproach->setItemData(4, _ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
00786 #else
00787                 _ui->comboBox_meshingApproach->setItemData(4, 0, Qt::UserRole - 1);
00788 #endif
00789 
00790                 if(_ui->comboBox_pipeline->currentIndex() == 0 && _ui->comboBox_meshingApproach->currentIndex()<2)
00791                 {
00792                         _ui->comboBox_meshingApproach->setCurrentIndex(3);
00793                 }
00794                 if(_ui->comboBox_pipeline->currentIndex() == 1 && (_ui->comboBox_meshingApproach->currentIndex()==2 || _ui->comboBox_meshingApproach->currentIndex()==3))
00795                 {
00796                         _ui->comboBox_meshingApproach->setCurrentIndex(1);
00797                 }
00798                 if(!_ui->checkBox_assemble->isChecked())
00799                 {
00800                         _ui->comboBox_meshingApproach->setCurrentIndex(_ui->comboBox_pipeline->currentIndex() == 1?0:3);
00801                 }
00802 
00803                 _ui->checkBox_poisson_outputPolygons->setDisabled(
00804                                         _ui->checkBox_binary->isEnabled() ||
00805                                         _ui->doubleSpinBox_meshDecimationFactor->value()!=0.0 ||
00806                                         _ui->spinBox_meshMaxPolygons->value()!=0 ||
00807                                         _ui->checkBox_textureMapping->isChecked());
00808 
00809                 _ui->checkBox_cleanMesh->setEnabled(_ui->comboBox_pipeline->currentIndex() == 1);
00810                 _ui->label_meshClean->setEnabled(_ui->comboBox_pipeline->currentIndex() == 1);
00811 
00812                 _ui->groupBox_gp3->setVisible(_ui->comboBox_pipeline->currentIndex() == 1 && _ui->comboBox_meshingApproach->currentIndex()==0);
00813                 _ui->groupBox_poisson->setVisible(_ui->comboBox_pipeline->currentIndex() == 1 && _ui->comboBox_meshingApproach->currentIndex()==1);
00814                 _ui->groupBox_cputsdf->setVisible(_ui->comboBox_pipeline->currentIndex() == 0 && _ui->comboBox_meshingApproach->currentIndex()==2);
00815                 _ui->groupBox_organized->setVisible(_ui->comboBox_pipeline->currentIndex() == 0 && _ui->comboBox_meshingApproach->currentIndex()==3);
00816                 _ui->groupBox_openchisel->setVisible(_ui->comboBox_meshingApproach->currentIndex()==4);
00817 
00818 #ifndef DISABLE_VTK
00819                 _ui->doubleSpinBox_meshDecimationFactor->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
00820                 _ui->label_meshDecimation->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
00821                 _ui->spinBox_meshMaxPolygons->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
00822                 _ui->label_meshMaxPolygons->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
00823 #endif
00824         }
00825 }
00826 
00827 void ExportCloudsDialog::selectDistortionModel()
00828 {
00829         QString dir = _ui->lineEdit_distortionModel->text();
00830         if(dir.isEmpty())
00831         {
00832                 dir = _workingDirectory;
00833         }
00834         QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Distortion model (*.bin *.txt)"));
00835         if(path.size())
00836         {
00837                 _ui->lineEdit_distortionModel->setText(path);
00838         }
00839 }
00840 
00841 void ExportCloudsDialog::setSaveButton()
00842 {
00843         _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(false);
00844         _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(true);
00845         _ui->checkBox_binary->setVisible(true);
00846         _ui->checkBox_binary->setEnabled(true);
00847         _ui->label_binaryFile->setVisible(true);
00848         _ui->checkBox_mesh_quad->setVisible(false);
00849         _ui->checkBox_mesh_quad->setEnabled(false);
00850         _ui->label_quad->setVisible(false);
00851         updateReconstructionFlavor();
00852 }
00853 
00854 void ExportCloudsDialog::setOkButton()
00855 {
00856         _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(true);
00857         _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(false);
00858         _ui->checkBox_binary->setVisible(false);
00859         _ui->checkBox_binary->setEnabled(false);
00860         _ui->label_binaryFile->setVisible(false);
00861         _ui->checkBox_mesh_quad->setVisible(true);
00862         _ui->checkBox_mesh_quad->setEnabled(true);
00863         _ui->label_quad->setVisible(true);
00864         updateReconstructionFlavor();
00865 }
00866 
00867 void ExportCloudsDialog::exportClouds(
00868                 const std::map<int, Transform> & poses,
00869                 const std::multimap<int, Link> & links,
00870                 const std::map<int, int> & mapIds,
00871                 const QMap<int, Signature> & cachedSignatures,
00872                 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
00873                 const std::map<int, LaserScan> & cachedScans,
00874                 const QString & workingDirectory,
00875                 const ParametersMap & parameters)
00876 {
00877         std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
00878         std::map<int, pcl::PolygonMesh::Ptr> meshes;
00879         std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
00880         std::vector<std::map<int, pcl::PointXY> > textureVertexToPixels;
00881 
00882         setSaveButton();
00883 
00884         if(getExportedClouds(
00885                         poses,
00886                         links,
00887                         mapIds,
00888                         cachedSignatures,
00889                         cachedClouds,
00890                         cachedScans,
00891                         workingDirectory,
00892                         parameters,
00893                         clouds,
00894                         meshes,
00895                         textureMeshes,
00896                         textureVertexToPixels))
00897         {
00898                 if(textureMeshes.size())
00899                 {
00900                         saveTextureMeshes(workingDirectory, poses, textureMeshes, cachedSignatures, textureVertexToPixels);
00901                 }
00902                 else if(meshes.size())
00903                 {
00904                         bool exportMeshes = true;
00905                         if(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked())
00906                         {
00907                                 QMessageBox::StandardButton r = QMessageBox::warning(this, tr("Exporting Texture Mesh"),
00908                                                 tr("No texture mesh could be created, do you want to continue with saving only the meshes (%1)?").arg(meshes.size()),
00909                                                 QMessageBox::Yes|QMessageBox::No, QMessageBox::Yes);
00910                                 exportMeshes = r == QMessageBox::Yes;
00911                         }
00912                         if(exportMeshes)
00913                         {
00914                                 saveMeshes(workingDirectory, poses, meshes, _ui->checkBox_binary->isChecked());
00915                         }
00916                 }
00917                 else
00918                 {
00919                         saveClouds(workingDirectory, poses, clouds, _ui->checkBox_binary->isChecked());
00920                 }
00921         }
00922         else if(!_canceled)
00923         {
00924                 _progressDialog->setAutoClose(false);
00925         }
00926         _progressDialog->setValue(_progressDialog->maximumSteps());
00927 }
00928 
00929 void ExportCloudsDialog::viewClouds(
00930                 const std::map<int, Transform> & poses,
00931                 const std::multimap<int, Link> & links,
00932                 const std::map<int, int> & mapIds,
00933                 const QMap<int, Signature> & cachedSignatures,
00934                 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
00935                 const std::map<int, LaserScan> & cachedScans,
00936                 const QString & workingDirectory,
00937                 const ParametersMap & parameters)
00938 {
00939         std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
00940         std::map<int, pcl::PolygonMesh::Ptr> meshes;
00941         std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
00942         std::vector<std::map<int, pcl::PointXY> > textureVertexToPixels;
00943 
00944         setOkButton();
00945 
00946         if(getExportedClouds(
00947                         poses,
00948                         links,
00949                         mapIds,
00950                         cachedSignatures,
00951                         cachedClouds,
00952                         cachedScans,
00953                         workingDirectory,
00954                         parameters,
00955                         clouds,
00956                         meshes,
00957                         textureMeshes,
00958                         textureVertexToPixels))
00959         {
00960                 QDialog * window = new QDialog(this->parentWidget()?this->parentWidget():this, Qt::Window);
00961                 window->setAttribute(Qt::WA_DeleteOnClose, true);
00962                 if(meshes.size())
00963                 {
00964                         window->setWindowTitle(tr("Meshes (%1 nodes)").arg(meshes.size()));
00965                 }
00966                 else
00967                 {
00968                         window->setWindowTitle(tr("Clouds (%1 nodes)").arg(clouds.size()));
00969                 }
00970                 window->setMinimumWidth(120);
00971                 window->setMinimumHeight(90);
00972                 window->resize(QDesktopWidget().availableGeometry(this).size() * 0.7);
00973 
00974                 CloudViewer * viewer = new CloudViewer(window);
00975                 if(_ui->comboBox_pipeline->currentIndex() == 0)
00976                 {
00977                         viewer->setBackfaceCulling(true, false);
00978                 }
00979                 viewer->setLighting(true);
00980                 viewer->setDefaultBackgroundColor(QColor(40, 40, 40, 255));
00981                 viewer->buildPickingLocator(true);
00982 
00983                 QVBoxLayout *layout = new QVBoxLayout();
00984                 layout->addWidget(viewer);
00985                 layout->setContentsMargins(0,0,0,0);
00986                 window->setLayout(layout);
00987                 connect(window, SIGNAL(finished(int)), viewer, SLOT(clear()));
00988 
00989                 window->show();
00990 
00991                 _progressDialog->appendText(tr("Opening visualizer..."));
00992                 QApplication::processEvents();
00993                 uSleep(500);
00994                 QApplication::processEvents();
00995 
00996                 if(textureMeshes.size())
00997                 {
00998                         viewer->setPolygonPicking(true);
00999                         std::map<int, cv::Mat> images;
01000                         std::map<int, std::vector<CameraModel> > calibrations;
01001                         for(QMap<int, Signature>::const_iterator iter=cachedSignatures.constBegin(); iter!=cachedSignatures.constEnd(); ++iter)
01002                         {
01003                                 std::vector<CameraModel> models;
01004                                 if(iter->sensorData().cameraModels().size())
01005                                 {
01006                                         models = iter->sensorData().cameraModels();
01007                                 }
01008                                 else if(iter->sensorData().stereoCameraModel().isValidForProjection())
01009                                 {
01010                                         models.push_back(iter->sensorData().stereoCameraModel().left());
01011                                 }
01012 
01013                                 if(!models.empty())
01014                                 {
01015                                         if(!iter->sensorData().imageRaw().empty())
01016                                         {
01017                                                 calibrations.insert(std::make_pair(iter.key(), models));
01018                                                 images.insert(std::make_pair(iter.key(), iter->sensorData().imageRaw()));
01019                                         }
01020                                         else if(!iter->sensorData().imageCompressed().empty())
01021                                         {
01022                                                 calibrations.insert(std::make_pair(iter.key(), models));
01023                                                 images.insert(std::make_pair(iter.key(), iter->sensorData().imageCompressed()));
01024                                         }
01025                                 }
01026                         }
01027                         int textureSize = 1024;
01028                         if(_ui->comboBox_meshingTextureSize->currentIndex() > 0)
01029                         {
01030                                 textureSize = 128 << _ui->comboBox_meshingTextureSize->currentIndex(); // start at 256
01031                         }
01032                         int blendingDecimation = 0;
01033                         if(_ui->checkBox_blending->isChecked())
01034                         {
01035                                 if(_ui->comboBox_blendingDecimation->currentIndex() > 0)
01036                                 {
01037                                         blendingDecimation = 1 << (_ui->comboBox_blendingDecimation->currentIndex()-1);
01038                                 }
01039                         }
01040 
01041                         for (std::map<int, pcl::TextureMesh::Ptr>::iterator iter = textureMeshes.begin(); iter != textureMeshes.end(); ++iter)
01042                         {
01043                                 pcl::TextureMesh::Ptr mesh = iter->second;
01044 
01045                                 // As CloudViewer is not supporting more than one texture per mesh, merge them all by default
01046                                 cv::Mat globalTexture;
01047                                 if (mesh->tex_materials.size() > 1)
01048                                 {
01049                                         cv::Mat globalTextures;
01050                                         globalTextures = util3d::mergeTextures(
01051                                                         *mesh,
01052                                                         images,
01053                                                         calibrations,
01054                                                         0,
01055                                                         _dbDriver,
01056                                                         textureSize,
01057                                                         1,
01058                                                         textureVertexToPixels,
01059                                                         _ui->checkBox_gainCompensation->isChecked(),
01060                                                         _ui->doubleSpinBox_gainBeta->value(),
01061                                                         _ui->checkBox_gainRGB->isChecked(),
01062                                                         _ui->checkBox_blending->isChecked(),
01063                                                         blendingDecimation,
01064                                                         _ui->spinBox_textureBrightnessContrastRatioLow->value(),
01065                                                         _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
01066                                                         _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked());
01067                                         if(globalTextures.rows == globalTextures.cols)
01068                                         {
01069                                                 globalTexture = globalTextures;
01070                                         }
01071                                 }
01072 
01073                                 _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)...").arg(iter->first).arg(mesh->tex_polygons.size()?mesh->tex_polygons[0].size():0));
01074                                 _progressDialog->incrementStep();
01075 
01076                                 // VTK issue:
01077                                 //  tex_coordinates should be linked to points, not
01078                                 //  polygon vertices. Points linked to multiple different TCoords (different textures) should
01079                                 //  be duplicated.
01080                                 for (unsigned int t = 0; t < mesh->tex_coordinates.size(); ++t)
01081                                 {
01082                                         if(mesh->tex_polygons[t].size())
01083                                         {
01084 
01085                                                 pcl::PointCloud<pcl::PointXYZ>::Ptr originalCloud(new pcl::PointCloud<pcl::PointXYZ>);
01086                                                 pcl::fromPCLPointCloud2(mesh->cloud, *originalCloud);
01087 
01088                                                 // make a cloud with as many points than polygon vertices
01089                                                 unsigned int nPoints = mesh->tex_coordinates[t].size();
01090                                                 UASSERT(nPoints == mesh->tex_polygons[t].size()*mesh->tex_polygons[t][0].vertices.size()); // assuming polygon size is constant!
01091 
01092                                                 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
01093                                                 cloud->resize(nPoints);
01094 
01095                                                 unsigned int oi = 0;
01096                                                 for (unsigned int i = 0; i < mesh->tex_polygons[t].size(); ++i)
01097                                                 {
01098                                                         pcl::Vertices & vertices = mesh->tex_polygons[t][i];
01099 
01100                                                         for(unsigned int j=0; j<vertices.vertices.size(); ++j)
01101                                                         {
01102                                                                 UASSERT(oi < cloud->size());
01103                                                                 UASSERT_MSG(vertices.vertices[j] < originalCloud->size(), uFormat("%d vs %d", vertices.vertices[j], (int)originalCloud->size()).c_str());
01104                                                                 cloud->at(oi) = originalCloud->at(vertices.vertices[j]);
01105                                                                 vertices.vertices[j] = oi; // new vertice index
01106                                                                 ++oi;
01107                                                         }
01108                                                 }
01109                                                 pcl::toPCLPointCloud2(*cloud, mesh->cloud);
01110                                         }
01111                                         else
01112                                         {
01113                                                 UWARN("No polygons for texture %d of mesh %d?!", t, iter->first);
01114                                         }
01115                                 }
01116 
01117                                 if (globalTexture.empty())
01118                                 {
01119                                         if(mesh->tex_materials.size()==1 &&
01120                                                 !mesh->tex_materials[0].tex_file.empty() &&
01121                                                 uIsInteger(mesh->tex_materials[0].tex_file, false))
01122                                         {
01123                                                 int textureId = uStr2Int(mesh->tex_materials[0].tex_file);
01124                                                 SensorData data;
01125                                                 if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
01126                                                 {
01127                                                         data = cachedSignatures.value(textureId).sensorData();
01128                                                 }
01129                                                 else if(_dbDriver)
01130                                                 {
01131                                                         _dbDriver->getNodeData(textureId, data, true, false, false, false);
01132                                                 }
01133                                                 UASSERT(!data.imageCompressed().empty());
01134                                                 data.uncompressDataConst(&globalTexture, 0);
01135                                                 UASSERT(!globalTexture.empty());
01136                                                 if (_ui->checkBox_gainCompensation->isChecked() && _compensator && _compensator->getIndex(textureId) >= 0)
01137                                                 {
01138                                                         _compensator->apply(textureId, globalTexture, _ui->checkBox_gainRGB->isChecked());
01139                                                 }
01140                                         }
01141                                         else
01142                                         {
01143                                                 _progressDialog->appendText(tr("No textures added to mesh %1!?").arg(iter->first), Qt::darkRed);
01144                                                 _progressDialog->setAutoClose(false);
01145                                         }
01146                                 }
01147 
01148                                 viewer->addCloudTextureMesh(uFormat("mesh%d",iter->first), mesh, globalTexture, iter->first>0?poses.at(iter->first):Transform::getIdentity());
01149                                 _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)... done.").arg(iter->first).arg(mesh->tex_polygons.size()?mesh->tex_polygons[0].size():0));
01150                                 QApplication::processEvents();
01151                         }
01152                 }
01153                 else if(meshes.size())
01154                 {
01155                         viewer->setPolygonPicking(true);
01156                         for(std::map<int, pcl::PolygonMesh::Ptr>::iterator iter = meshes.begin(); iter!=meshes.end(); ++iter)
01157                         {
01158                                 _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)...").arg(iter->first).arg(iter->second->polygons.size()));
01159                                 _progressDialog->incrementStep();
01160                                 bool isRGB = false;
01161                                 for(unsigned int i=0; i<iter->second->cloud.fields.size(); ++i)
01162                                 {
01163                                         if(iter->second->cloud.fields[i].name.compare("rgb") == 0)
01164                                         {
01165                                                 isRGB=true;
01166                                                 break;
01167                                         }
01168                                 }
01169                                 if(isRGB)
01170                                 {
01171                                         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
01172                                         pcl::fromPCLPointCloud2(iter->second->cloud, *cloud);
01173                                         viewer->addCloudMesh(uFormat("mesh%d",iter->first), cloud, iter->second->polygons, iter->first>0?poses.at(iter->first):Transform::getIdentity());
01174                                 }
01175                                 else
01176                                 {
01177                                         pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
01178                                         pcl::fromPCLPointCloud2(iter->second->cloud, *cloud);
01179                                         viewer->addCloudMesh(uFormat("mesh%d",iter->first), cloud, iter->second->polygons, iter->first>0?poses.at(iter->first):Transform::getIdentity());
01180                                 }
01181                                 _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)... done.").arg(iter->first).arg(iter->second->polygons.size()));
01182                                 QApplication::processEvents();
01183                         }
01184                 }
01185                 else if(clouds.size())
01186                 {
01187                         for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::iterator iter = clouds.begin(); iter!=clouds.end(); ++iter)
01188                         {
01189                                 _progressDialog->appendText(tr("Viewing the cloud %1 (%2 points)...").arg(iter->first).arg(iter->second->size()));
01190                                 _progressDialog->incrementStep();
01191 
01192                                 QColor color = Qt::gray;
01193                                 int mapId = uValue(mapIds, iter->first, -1);
01194                                 if(mapId >= 0)
01195                                 {
01196                                         color = (Qt::GlobalColor)(mapId % 12 + 7 );
01197                                 }
01198                                 viewer->addCloud(uFormat("cloud%d",iter->first), iter->second, iter->first>0?poses.at(iter->first):Transform::getIdentity());
01199                                 viewer->setCloudPointSize(uFormat("cloud%d",iter->first), 2);
01200                                 _progressDialog->appendText(tr("Viewing the cloud %1 (%2 points)... done.").arg(iter->first).arg(iter->second->size()));
01201                         }
01202                 }
01203                 viewer->update();
01204         }
01205         else
01206         {
01207                 _progressDialog->setAutoClose(false);
01208         }
01209         _progressDialog->setValue(_progressDialog->maximumSteps());
01210 }
01211 
01212 int ExportCloudsDialog::getTextureSize() const
01213 {
01214         int textureSize = 1024;
01215         if(_ui->comboBox_meshingTextureSize->currentIndex() > 0)
01216         {
01217                 textureSize = 128 << _ui->comboBox_meshingTextureSize->currentIndex(); // start at 256
01218         }
01219         return textureSize;
01220 }
01221 int ExportCloudsDialog::getMaxTextures() const
01222 {
01223         return _ui->spinBox_mesh_maxTextures->value();
01224 }
01225 bool ExportCloudsDialog::isGainCompensation() const
01226 {
01227         return _ui->checkBox_gainCompensation->isChecked();
01228 }
01229 double ExportCloudsDialog::getGainBeta() const
01230 {
01231         return _ui->doubleSpinBox_gainBeta->value();
01232 }
01233 bool ExportCloudsDialog::isGainRGB() const
01234 {
01235         return _ui->checkBox_gainRGB->isChecked();
01236 }
01237 bool ExportCloudsDialog::isBlending() const
01238 {
01239         return _ui->checkBox_blending->isChecked();
01240 }
01241 int ExportCloudsDialog::getBlendingDecimation() const
01242 {
01243         int blendingDecimation = 0;
01244         if(_ui->checkBox_blending->isChecked())
01245         {
01246                 if(_ui->comboBox_blendingDecimation->currentIndex() > 0)
01247                 {
01248                         blendingDecimation = 1 << (_ui->comboBox_blendingDecimation->currentIndex()-1);
01249                 }
01250         }
01251         return blendingDecimation;
01252 }
01253 int ExportCloudsDialog::getTextureBrightnessConstrastRatioLow() const
01254 {
01255         return _ui->spinBox_textureBrightnessContrastRatioLow->value();
01256 }
01257 int ExportCloudsDialog::getTextureBrightnessConstrastRatioHigh() const
01258 {
01259         return _ui->spinBox_textureBrightnessContrastRatioHigh->value();
01260 }
01261 bool ExportCloudsDialog::isExposeFusion() const
01262 {
01263         return _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked();
01264 }
01265 
01266 bool ExportCloudsDialog::removeDirRecursively(const QString & dirName)
01267 {
01268     bool result = true;
01269     QDir dir(dirName);
01270 
01271     if (dir.exists(dirName)) {
01272         Q_FOREACH(QFileInfo info, dir.entryInfoList(QDir::NoDotAndDotDot | QDir::System | QDir::Hidden  | QDir::AllDirs | QDir::Files, QDir::DirsFirst)) {
01273             if (info.isDir()) {
01274                 result = removeDirRecursively(info.absoluteFilePath());
01275             }
01276             else {
01277                 result = QFile::remove(info.absoluteFilePath());
01278             }
01279 
01280             if (!result) {
01281                 return result;
01282             }
01283         }
01284         result = dir.rmdir(dirName);
01285     }
01286     return result;
01287 }
01288 
01289 bool ExportCloudsDialog::getExportedClouds(
01290                 const std::map<int, Transform> & poses,
01291                 const std::multimap<int, Link> & links,
01292                 const std::map<int, int> & mapIds,
01293                 const QMap<int, Signature> & cachedSignatures,
01294                 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
01295                 const std::map<int, LaserScan> & cachedScans,
01296                 const QString & workingDirectory,
01297                 const ParametersMap & parameters,
01298                 std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & cloudsWithNormals,
01299                 std::map<int, pcl::PolygonMesh::Ptr> & meshes,
01300                 std::map<int, pcl::TextureMesh::Ptr> & textureMeshes,
01301                 std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels)
01302 {
01303         _canceled = false;
01304         _workingDirectory = workingDirectory;
01305         _ui->checkBox_regenerate->setEnabled(true);
01306         if(cachedSignatures.empty() && _dbDriver)
01307         {
01308                 _ui->checkBox_regenerate->setChecked(true);
01309                 _ui->checkBox_regenerate->setEnabled(false);
01310         }
01311         if(_compensator)
01312         {
01313                 delete _compensator;
01314                 _compensator = 0;
01315         }
01316         if(this->exec() == QDialog::Accepted)
01317         {
01318                 if(poses.empty())
01319                 {
01320                         QMessageBox::critical(this, tr("Creating clouds..."), tr("Poses are null! Cannot export/view clouds."));
01321                         return false;
01322                 }
01323                 _progressDialog->resetProgress();
01324                 _progressDialog->show();
01325                 int mul = 1;
01326                 if(_ui->checkBox_meshing->isChecked())
01327                 {
01328                         mul+=1;
01329                 }
01330                 if(_ui->checkBox_assemble->isChecked())
01331                 {
01332                         mul+=1;
01333                 }
01334 
01335                 if(_ui->checkBox_subtraction->isChecked())
01336                 {
01337                         mul+=1;
01338                 }
01339                 if(_ui->checkBox_textureMapping->isChecked())
01340                 {
01341                         mul+=1;
01342                 }
01343                 if(_ui->checkBox_gainCompensation->isChecked())
01344                 {
01345                         mul+=1;
01346                 }
01347                 if(_ui->checkBox_mesh_quad->isEnabled()) // when enabled we are viewing the clouds
01348                 {
01349                         mul+=1;
01350                 }
01351                 _progressDialog->setMaximumSteps(int(poses.size())*mul+1);
01352 
01353                 bool loadClouds = true;
01354 #ifdef RTABMAP_OPENCHISEL
01355                 if(_ui->comboBox_meshingApproach->currentIndex()==4 && _ui->checkBox_assemble->isChecked())
01356                 {
01357                         loadClouds = !_ui->checkBox_fromDepth->isChecked();
01358                 }
01359 #endif
01360 
01361                 bool has2dScans = false;
01362                 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
01363                 if(loadClouds)
01364                 {
01365                         clouds = this->getClouds(
01366                                         poses,
01367                                         cachedSignatures,
01368                                         cachedClouds,
01369                                         cachedScans,
01370                                         parameters,
01371                                         has2dScans);
01372                 }
01373                 else
01374                 {
01375                         // just create empty clouds
01376                         for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
01377                         {
01378                                 clouds.insert(std::make_pair(iter->first,
01379                                                 std::make_pair(
01380                                                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr(new pcl::PointCloud<pcl::PointXYZRGBNormal>),
01381                                                                 pcl::IndicesPtr(new std::vector<int>))));
01382 
01383                         }
01384                 }
01385 
01386                 std::set<int> validCameras = uKeysSet(clouds);
01387 
01388                 UDEBUG("");
01389                 if(_canceled)
01390                 {
01391                         return false;
01392                 }
01393 
01394                 if(clouds.empty())
01395                 {
01396                         _progressDialog->setAutoClose(false);
01397                         if(_ui->checkBox_regenerate->isEnabled() && !_ui->checkBox_regenerate->isChecked())
01398                         {
01399                                 QMessageBox::warning(this, tr("Creating clouds..."), tr("Could create clouds for %1 node(s). You "
01400                                                 "may want to activate clouds regeneration option.").arg(poses.size()));
01401                         }
01402                         else
01403                         {
01404                                 QMessageBox::warning(this, tr("Creating clouds..."), tr("Could not create clouds for %1 "
01405                                                 "node(s). The cache may not contain point cloud data. Try re-downloading the map.").arg(poses.size()));
01406                         }
01407                         return false;
01408                 }
01409 
01410                 UDEBUG("");
01411                 if(_ui->checkBox_gainCompensation->isChecked() && _ui->checkBox_fromDepth->isChecked() && clouds.size() > 1 &&
01412                                 // Do compensation later if we are merging textures on a dense assembled cloud
01413                                 !(_ui->checkBox_meshing->isChecked() &&
01414                                         _ui->checkBox_textureMapping->isEnabled() &&
01415                                         _ui->checkBox_textureMapping->isChecked() &&
01416                                         _ui->comboBox_pipeline->currentIndex()==1 &&
01417                                         _ui->checkBox_assemble->isChecked() &&
01418                                         _ui->comboBox_meshingTextureSize->isEnabled() &&
01419                                         _ui->comboBox_meshingTextureSize->currentIndex() > 0) &&
01420                                 // Don't do compensation if clouds are in camera frame
01421                                 !(_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex()==2))
01422                 {
01423                         UASSERT(_compensator == 0);
01424                         _compensator = new GainCompensator(_ui->doubleSpinBox_gainRadius->value(), _ui->doubleSpinBox_gainOverlap->value(), 0.01, _ui->doubleSpinBox_gainBeta->value());
01425 
01426                         if(_ui->checkBox_gainFull->isChecked())
01427                         {
01428                                 _progressDialog->appendText(tr("Full gain compensation of %1 clouds...").arg(clouds.size()));
01429                         }
01430                         else
01431                         {
01432                                 _progressDialog->appendText(tr("Gain compensation of %1 clouds...").arg(clouds.size()));
01433                         }
01434                         QApplication::processEvents();
01435                         uSleep(100);
01436                         QApplication::processEvents();
01437 
01438                         if(_ui->checkBox_gainFull->isChecked())
01439                         {
01440                                 std::multimap<int, Link> allLinks;
01441                                 for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator iter=clouds.begin(); iter!=clouds.end(); ++iter)
01442                                 {
01443                                         int from = iter->first;
01444                                         std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator jter = iter;
01445                                         ++jter;
01446                                         for(;jter!=clouds.end(); ++jter)
01447                                         {
01448                                                 int to = jter->first;
01449                                                 allLinks.insert(std::make_pair(from, Link(from, to, Link::kUserClosure, poses.at(from).inverse()*poses.at(to))));
01450                                         }
01451                                 }
01452 
01453                                 _compensator->feed(clouds, allLinks);
01454                         }
01455                         else
01456                         {
01457                                 _compensator->feed(clouds, links);
01458                         }
01459 
01460                         if(!(_ui->checkBox_meshing->isChecked() &&
01461                                  _ui->checkBox_textureMapping->isEnabled() &&
01462                                  _ui->checkBox_textureMapping->isChecked()))
01463                         {
01464                                 _progressDialog->appendText(tr("Applying gain compensation..."));
01465                                 for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator jter=clouds.begin();jter!=clouds.end(); ++jter)
01466                                 {
01467                                         if(jter!=clouds.end())
01468                                         {
01469                                                 double gain = _compensator->getGain(jter->first);;
01470                                                 _compensator->apply(jter->first, jter->second.first, jter->second.second, _ui->checkBox_gainRGB->isChecked());
01471 
01472                                                 _progressDialog->appendText(tr("Cloud %1 has gain %2").arg(jter->first).arg(gain));
01473                                                 _progressDialog->incrementStep();
01474                                                 QApplication::processEvents();
01475                                                 if(_canceled)
01476                                                 {
01477                                                         return false;
01478                                                 }
01479                                         }
01480                                 }
01481                         }
01482                 }
01483 
01484                 UDEBUG("");
01485                 std::map<int, Transform> normalViewpoints = poses;
01486                 if(_ui->checkBox_assemble->isChecked())
01487                 {
01488                         // Adjust view points with local transforms
01489                         for(std::map<int, Transform>::iterator iter= normalViewpoints.begin(); iter!=normalViewpoints.end(); ++iter)
01490                         {
01491                                 if(_ui->checkBox_fromDepth->isChecked())
01492                                 {
01493                                         std::vector<CameraModel> models;
01494                                         StereoCameraModel stereoModel;
01495                                         if(cachedSignatures.contains(iter->first))
01496                                         {
01497                                                 const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
01498                                                 models = data.cameraModels();
01499                                                 stereoModel = data.stereoCameraModel();
01500                                         }
01501                                         else if(_dbDriver)
01502                                         {
01503                                                 _dbDriver->getCalibration(iter->first, models, stereoModel);
01504                                         }
01505 
01506                                         if(models.size() && !models[0].localTransform().isNull())
01507                                         {
01508                                                 iter->second *= models[0].localTransform();
01509                                         }
01510                                         else if(!stereoModel.localTransform().isNull())
01511                                         {
01512                                                 iter->second *= stereoModel.localTransform();
01513                                         }
01514                                 }
01515                                 else
01516                                 {
01517                                         if(uContains(cachedScans, iter->first))
01518                                         {
01519                                                 iter->second *= cachedScans.at(iter->first).localTransform();
01520                                         }
01521                                         else if(cachedSignatures.contains(iter->first))
01522                                         {
01523                                                 const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
01524                                                 if(!data.laserScanCompressed().isEmpty())
01525                                                 {
01526                                                         iter->second *= data.laserScanCompressed().localTransform();
01527                                                 }
01528                                                 else if(!data.laserScanRaw().isEmpty())
01529                                                 {
01530                                                         iter->second *= data.laserScanRaw().localTransform();
01531                                                 }
01532                                         }
01533                                         else if(_dbDriver)
01534                                         {
01535                                                 LaserScan scan;
01536                                                 _dbDriver->getLaserScanInfo(iter->first, scan);
01537                                                 iter->second *= scan.localTransform();
01538                                         }
01539                                 }
01540                         }
01541                 }
01542 
01543                 UDEBUG("");
01544                 pcl::PointCloud<pcl::PointXYZ>::Ptr rawAssembledCloud(new pcl::PointCloud<pcl::PointXYZ>);
01545                 std::vector<int> rawCameraIndices;
01546                 if(_ui->checkBox_assemble->isChecked() &&
01547                    !((_ui->comboBox_pipeline->currentIndex()==0 || _ui->comboBox_meshingApproach->currentIndex()==4) && _ui->checkBox_meshing->isChecked()))
01548                 {
01549                         _progressDialog->appendText(tr("Assembling %1 clouds...").arg(clouds.size()));
01550                         QApplication::processEvents();
01551 
01552                         int i =0;
01553                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr assembledCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
01554                         for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator iter=clouds.begin();
01555                                 iter!= clouds.end();
01556                                 ++iter)
01557                         {
01558                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformed(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
01559                                 if(iter->second.first->isOrganized())
01560                                 {
01561                                         pcl::copyPointCloud(*iter->second.first, *iter->second.second, *transformed);
01562                                         transformed = util3d::transformPointCloud(transformed, poses.at(iter->first));
01563                                 }
01564                                 else
01565                                 {
01566                                         // it looks like that using only transformPointCloud with indices
01567                                         // flushes the colors, so we should extract points before... maybe a too old PCL version
01568                                         pcl::copyPointCloud(*iter->second.first, *iter->second.second, *transformed);
01569                                         transformed = rtabmap::util3d::transformPointCloud(transformed, poses.at(iter->first));
01570                                 }
01571 
01572                                 *assembledCloud += *transformed;
01573                                 rawCameraIndices.resize(assembledCloud->size(), iter->first);
01574 
01575                                 _progressDialog->appendText(tr("Assembled cloud %1, total=%2 (%3/%4).").arg(iter->first).arg(assembledCloud->size()).arg(++i).arg(clouds.size()));
01576                                 _progressDialog->incrementStep();
01577                                 QApplication::processEvents();
01578                                 if(_canceled)
01579                                 {
01580                                         return false;
01581                                 }
01582                         }
01583 
01584                         assembledCloud->is_dense = true;
01585                         pcl::copyPointCloud(*assembledCloud, *rawAssembledCloud);
01586 
01587                         if(_ui->doubleSpinBox_voxelSize_assembled->value())
01588                         {
01589                                 _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...")
01590                                                 .arg(assembledCloud->size())
01591                                                 .arg(_ui->doubleSpinBox_voxelSize_assembled->value()));
01592                                 QApplication::processEvents();
01593                                 unsigned int before = assembledCloud->size();
01594                                 assembledCloud = util3d::voxelize(
01595                                                 assembledCloud,
01596                                                 _ui->doubleSpinBox_voxelSize_assembled->value());
01597                                 _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...done! (%3 points)")
01598                                                 .arg(before)
01599                                                 .arg(_ui->doubleSpinBox_voxelSize_assembled->value())
01600                                                 .arg(assembledCloud->size()));
01601                         }
01602 
01603                         clouds.clear();
01604                         pcl::IndicesPtr indices(new std::vector<int>);
01605                         indices->resize(assembledCloud->size());
01606                         for(unsigned int i=0; i<indices->size(); ++i)
01607                         {
01608                                 indices->at(i) = i;
01609                         }
01610 
01611                         if(!_ui->checkBox_fromDepth->isChecked() && !has2dScans)
01612                         {
01613                                 // recompute normals
01614                                 pcl::PointCloud<pcl::PointXYZ>::Ptr cloudWithoutNormals(new pcl::PointCloud<pcl::PointXYZ>);
01615                                 pcl::copyPointCloud(*assembledCloud, *cloudWithoutNormals);
01616                                 pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value());
01617 
01618                                 UASSERT(assembledCloud->size() == normals->size());
01619                                 for(unsigned int i=0; i<normals->size(); ++i)
01620                                 {
01621                                         assembledCloud->points[i].normal_x = normals->points[i].normal_x;
01622                                         assembledCloud->points[i].normal_y = normals->points[i].normal_y;
01623                                         assembledCloud->points[i].normal_z = normals->points[i].normal_z;
01624                                 }
01625 
01626                                 // adjust with point of views
01627                                 util3d::adjustNormalsToViewPoints(
01628                                                                                         normalViewpoints,
01629                                                                                         rawAssembledCloud,
01630                                                                                         rawCameraIndices,
01631                                                                                         assembledCloud);
01632                         }
01633 
01634                         clouds.insert(std::make_pair(0, std::make_pair(assembledCloud, indices)));
01635                 }
01636 
01637                 UDEBUG("");
01638                 if(_canceled)
01639                 {
01640                         return false;
01641                 }
01642 
01643                 if(_ui->checkBox_smoothing->isEnabled() && _ui->checkBox_smoothing->isChecked() && !has2dScans)
01644                 {
01645                         _progressDialog->appendText(tr("Smoothing the surface using Moving Least Squares (MLS) algorithm... "
01646                                         "[search radius=%1m voxel=%2m]").arg(_ui->doubleSpinBox_mlsRadius->value()).arg(_ui->doubleSpinBox_voxelSize_assembled->value()));
01647                         QApplication::processEvents();
01648                         uSleep(100);
01649                         QApplication::processEvents();
01650                 }
01651 
01652                 //fill cloudWithNormals
01653                 for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator iter=clouds.begin();
01654                         iter!= clouds.end();)
01655                 {
01656                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudWithNormals = iter->second.first;
01657 
01658                         if(_ui->checkBox_smoothing->isEnabled() && _ui->checkBox_smoothing->isChecked() && !has2dScans)
01659                         {
01660                                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals(new pcl::PointCloud<pcl::PointXYZRGB>);
01661                                 if(iter->second.second->size())
01662                                 {
01663                                         pcl::copyPointCloud(*cloudWithNormals, *iter->second.second, *cloudWithoutNormals);
01664                                 }
01665                                 else
01666                                 {
01667                                         pcl::copyPointCloud(*cloudWithNormals, *cloudWithoutNormals);
01668                                 }
01669 
01670                                 _progressDialog->appendText(tr("Smoothing (MLS) the cloud (%1 points)...").arg(cloudWithNormals->size()));
01671                                 QApplication::processEvents();
01672                                 uSleep(100);
01673                                 QApplication::processEvents();
01674                                 if(_canceled)
01675                                 {
01676                                         return false;
01677                                 }
01678 
01679                                 cloudWithNormals = util3d::mls(
01680                                                 cloudWithoutNormals,
01681                                                 (float)_ui->doubleSpinBox_mlsRadius->value(),
01682                                                 _ui->spinBox_polygonialOrder->value(),
01683                                                 _ui->comboBox_upsamplingMethod->currentIndex(),
01684                                                 (float)_ui->doubleSpinBox_sampleRadius->value(),
01685                                                 (float)_ui->doubleSpinBox_sampleStep->value(),
01686                                                 _ui->spinBox_randomPoints->value(),
01687                                                 (float)_ui->doubleSpinBox_dilationVoxelSize->value(),
01688                                                 _ui->spinBox_dilationSteps->value());
01689 
01690                                 // make sure there are no nans
01691                                 UDEBUG("NaNs filtering... size before = %d", cloudWithNormals->size());
01692                                 cloudWithNormals = util3d::removeNaNNormalsFromPointCloud(cloudWithNormals);
01693                                 UDEBUG("NaNs filtering... size after = %d", cloudWithNormals->size());
01694 
01695                                 if(_ui->checkBox_assemble->isChecked())
01696                                 {
01697                                         // Re-voxelize to make sure to have uniform density
01698                     if(_ui->doubleSpinBox_mls_outputVoxelSize->value())
01699                                         {
01700                                                 _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...")
01701                                                                 .arg(cloudWithNormals->size())
01702                                                                 .arg(_ui->doubleSpinBox_mls_outputVoxelSize->value()));
01703                                                 QApplication::processEvents();
01704 
01705                                                 cloudWithNormals = util3d::voxelize(
01706                                                                 cloudWithNormals,
01707                                                                 _ui->doubleSpinBox_mls_outputVoxelSize->value());
01708                                         }
01709                                 
01710                                         _progressDialog->appendText(tr("Update %1 normals with %2 camera views...").arg(cloudWithNormals->size()).arg(poses.size()));
01711 
01712                                         util3d::adjustNormalsToViewPoints(
01713                                                         normalViewpoints,
01714                                                         rawAssembledCloud,
01715                                                         rawCameraIndices,
01716                                                         cloudWithNormals);
01717                                 }
01718                         }
01719                         else if(iter->second.first->isOrganized() && _ui->checkBox_filtering->isChecked())
01720                         {
01721                                 cloudWithNormals = util3d::extractIndices(iter->second.first, iter->second.second, false, true);
01722                         }
01723 
01724                         cloudsWithNormals.insert(std::make_pair(iter->first, cloudWithNormals));
01725 
01726                         // clear memory
01727                         clouds.erase(iter++);
01728 
01729                         _progressDialog->incrementStep();
01730                         QApplication::processEvents();
01731                         if(_canceled)
01732                         {
01733                                 return false;
01734                         }
01735                 }
01736 
01737                 UDEBUG("");
01738 #ifdef RTABMAP_CPUTSDF
01739                 cpu_tsdf::TSDFVolumeOctree::Ptr tsdf;
01740 #endif
01741 #ifdef RTABMAP_OPENCHISEL
01742                 chisel::ChiselPtr chiselMap;
01743                 chisel::ProjectionIntegrator projectionIntegrator;
01744 #endif
01745 
01746                 //used for organized texturing below
01747                 std::map<int, std::vector<int> > organizedIndices;
01748                 std::map<int, cv::Size> organizedCloudSizes;
01749 
01750                 //mesh
01751                 UDEBUG("Meshing=%d", _ui->checkBox_meshing->isChecked()?1:0);
01752                 if(_ui->checkBox_meshing->isChecked() && !has2dScans)
01753                 {
01754 
01755 #ifdef RTABMAP_OPENCHISEL
01756                         if(_ui->comboBox_meshingApproach->currentIndex()==4 && _ui->checkBox_assemble->isChecked())
01757                         {
01758                                 _progressDialog->appendText(tr("Creating TSDF volume with OpenChisel... "));
01759 
01760                                 QApplication::processEvents();
01761                                 uSleep(100);
01762                                 QApplication::processEvents();
01763 
01764                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
01765                                 std::vector<pcl::Vertices> mergedPolygons;
01766 
01767                                 int cloudsAdded = 1;
01768                                 for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::iterator iter=cloudsWithNormals.begin();
01769                                         iter!= cloudsWithNormals.end();
01770                                         ++iter,++cloudsAdded)
01771                                 {
01772                                         std::vector<CameraModel> models;
01773                                         StereoCameraModel stereoModel;
01774                                         bool cacheHasCompressedImage = false;
01775                                         LaserScan scanInfo;
01776                                         if(cachedSignatures.contains(iter->first))
01777                                         {
01778                                                 const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
01779                                                 models = data.cameraModels();
01780                                                 cacheHasCompressedImage = !data.imageCompressed().empty();
01781                                                 scanInfo = !data.laserScanRaw().isEmpty()?data.laserScanRaw():data.laserScanCompressed();
01782                                         }
01783                                         else if(_dbDriver)
01784                                         {
01785                                                 _dbDriver->getCalibration(iter->first, models, stereoModel);
01786                                                 _dbDriver->getLaserScanInfo(iter->first, scanInfo);
01787                                         }
01788 
01789                                         if(chiselMap.get() == 0)
01790                                         {
01791                                                 UDEBUG("");
01792                                                 int chunkSizeX = _ui->spinBox_openchisel_chunk_size_x->value();
01793                                                 int chunkSizeY = _ui->spinBox_openchisel_chunk_size_y->value();
01794                                                 int chunkSizeZ = _ui->spinBox_openchisel_chunk_size_z->value();
01795                                                 float voxelResolution = _ui->doubleSpinBox_voxelSize_assembled->value();
01796                                                 if(voxelResolution <=0.0f)
01797                                                 {
01798                                                         _progressDialog->appendText(tr("OpenChisel: Voxel size should not be null!"), Qt::darkYellow);
01799                                                         _progressDialog->setAutoClose(false);
01800                                                         break;
01801                                                 }
01802                                                 bool useColor = _ui->checkBox_fromDepth->isChecked();
01803                                                 chiselMap.reset(new chisel::Chisel(Eigen::Vector3i(chunkSizeX, chunkSizeY, chunkSizeZ), voxelResolution, useColor));
01804                                                 double truncationDistConst = _ui->doubleSpinBox_openchisel_truncation_constant->value();
01805                                                 double truncationDistLinear = _ui->doubleSpinBox_openchisel_truncation_linear->value();
01806                                                 double truncationDistQuad = _ui->doubleSpinBox_openchisel_truncation_quadratic->value();
01807                                                 double truncationDistScale = _ui->doubleSpinBox_openchisel_truncation_scale->value();
01808                                                 int weight = _ui->spinBox_openchisel_integration_weight->value();
01809                                                 bool useCarving = _ui->checkBox_openchisel_use_voxel_carving->isChecked();
01810                                                 double carvingDist = _ui->doubleSpinBox_openchisel_carving_dist_m->value();
01811                                                 chisel::Vec4 truncation(truncationDistQuad, truncationDistLinear, truncationDistConst, truncationDistScale);
01812                                                 UDEBUG("If crashing just after this message, make sure PCL and OpenChisel are built both with -march=native or both without -march=native");
01813                                                 projectionIntegrator.SetCentroids(chiselMap->GetChunkManager().GetCentroids());
01814                                                 projectionIntegrator.SetTruncator(chisel::TruncatorPtr(new chisel::QuadraticTruncator(truncation(0), truncation(1), truncation(2), truncation(3))));
01815                                                 projectionIntegrator.SetWeighter(chisel::WeighterPtr(new chisel::ConstantWeighter(weight)));
01816                                                 projectionIntegrator.SetCarvingDist(carvingDist);
01817                                                 projectionIntegrator.SetCarvingEnabled(useCarving);
01818                                         }
01819 
01820                                         UDEBUG("");
01821                                         double nearPlaneDist = _ui->doubleSpinBox_openchisel_near_plane_dist->value();
01822                                         double farPlaneDist = _ui->doubleSpinBox_openchisel_far_plane_dist->value();
01823                                         if(_ui->checkBox_fromDepth->isChecked())
01824                                         {
01825                                                 if(models.size() == 1 && !models[0].localTransform().isNull())
01826                                                 {
01827                                                         // get just the depth
01828                                                         cv::Mat rgb;
01829                                                         cv::Mat depth;
01830                                                         if(cacheHasCompressedImage)
01831                                                         {
01832                                                                 cachedSignatures.find(iter->first)->sensorData().uncompressDataConst(&rgb, &depth);
01833                                                         }
01834                                                         else if(_dbDriver)
01835                                                         {
01836                                                                 SensorData data;
01837                                                                 _dbDriver->getNodeData(iter->first, data, true, false, false, false);
01838                                                                 data.uncompressDataConst(&rgb, &depth);
01839                                                         }
01840                                                         if(!rgb.empty() && !depth.empty())
01841                                                         {
01842                                                                 CameraModel rgbModel = models[0];
01843                                                                 CameraModel depthModel = rgbModel;
01844                                                                 if(rgb.cols > depth.cols)
01845                                                                 {
01846                                                                         UASSERT(rgb.cols % depth.cols == 0);
01847                                                                         depthModel = depthModel.scaled(double(depth.cols)/double(rgb.cols));
01848                                                                 }
01849 
01850                                                                 if(depth.type() == CV_16UC1)
01851                                                                 {
01852                                                                         depth = util2d::cvtDepthToFloat(depth);
01853                                                                 }
01854 
01855                                                                 std::shared_ptr<chisel::ColorImage<unsigned char> > colorChisel = colorImageToChisel(rgb);
01856                                                                 std::shared_ptr<chisel::DepthImage<float> > depthChisel = depthImageToChisel(depth);
01857 
01858                                                                 chisel::PinholeCamera cameraColor = cameraModelToChiselCamera(rgbModel);
01859                                                                 chisel::PinholeCamera cameraDepth = cameraModelToChiselCamera(depthModel);
01860                                                                 cameraColor.SetNearPlane(nearPlaneDist);
01861                                                                 cameraColor.SetFarPlane(farPlaneDist);
01862                                                                 cameraDepth.SetNearPlane(nearPlaneDist);
01863                                                                 cameraDepth.SetFarPlane(farPlaneDist);
01864 
01865                                                                 chisel::Transform  pose_rel_to_first_frame = (poses.at(iter->first)*models[0].localTransform()).toEigen3f();
01866                                                                 chiselMap->IntegrateDepthScanColor<float, unsigned char>(projectionIntegrator, depthChisel, pose_rel_to_first_frame, cameraDepth, colorChisel, pose_rel_to_first_frame, cameraColor);
01867                                                                 UDEBUG("");
01868                                                         }
01869                                                         else
01870                                                         {
01871                                                                 _progressDialog->appendText(tr("OpenChisel: Depth and RGB images not found for %1!").arg(iter->first), Qt::darkYellow);
01872                                                         }
01873                                                 }
01874                                                 else
01875                                                 {
01876                                                         _progressDialog->appendText(tr("OpenChisel: Invalid camera model for cloud %1! Only single RGB-D camera supported.").arg(iter->first), Qt::darkYellow);
01877                                                         _progressDialog->setAutoClose(false);
01878                                                         break;
01879                                                 }
01880                                         }
01881                                         else if(!scanInfo.localTransform().isNull())
01882                                         {
01883                                                 chisel::PointCloudPtr chiselCloud = pointCloudRGBToChisel(*iter->second, scanInfo.localTransform().inverse());
01884                                                 chisel::Transform  pose_rel_to_first_frame = (poses.at(iter->first)*scanInfo.localTransform()).toEigen3f();
01885                                                 chiselMap->IntegratePointCloud(projectionIntegrator, *chiselCloud, pose_rel_to_first_frame, farPlaneDist);
01886                                                 UDEBUG("");
01887                                         }
01888                                         else
01889                                         {
01890                                                 _progressDialog->appendText(tr("OpenChisel: not valid scan info for cloud %1!").arg(iter->first), Qt::darkYellow);
01891                                                 _progressDialog->setAutoClose(false);
01892                                                 break;
01893                                         }
01894                                         chiselMap->UpdateMeshes();
01895                                         UDEBUG("");
01896                                         _progressDialog->appendText(tr("OpenChisel: Integrated cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
01897 
01898                                         _progressDialog->incrementStep();
01899                                         QApplication::processEvents();
01900                                         if(_canceled)
01901                                         {
01902                                                 return false;
01903                                         }
01904                                 }
01905                         }
01906                         else
01907 #endif
01908 
01909                         if(_ui->comboBox_pipeline->currentIndex() == 0)
01910                         {
01911                                 if(_ui->comboBox_meshingApproach->currentIndex()==2)
01912                                 {
01913                                         _progressDialog->appendText(tr("Creating TSDF volume with CPUTSDF... "));
01914                                 }
01915                                 else
01916                                 {
01917                                         _progressDialog->appendText(tr("Organized fast mesh... "));
01918                                 }
01919                                 QApplication::processEvents();
01920                                 uSleep(100);
01921                                 QApplication::processEvents();
01922 
01923                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
01924                                 std::vector<pcl::Vertices> mergedPolygons;
01925 
01926                                 int cloudsAdded = 1;
01927                                 for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::iterator iter=cloudsWithNormals.begin();
01928                                         iter!= cloudsWithNormals.end();
01929                                         ++iter,++cloudsAdded)
01930                                 {
01931                                         if(iter->second->isOrganized())
01932                                         {
01933                                                 if(iter->second->size())
01934                                                 {
01935                                                         Eigen::Vector3f viewpoint(0.0f,0.0f,0.0f);
01936 
01937                                                         std::vector<CameraModel> models;
01938                                                         StereoCameraModel stereoModel;
01939                                                         if(cachedSignatures.contains(iter->first))
01940                                                         {
01941                                                                 const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
01942                                                                 models = data.cameraModels();
01943                                                                 stereoModel = data.stereoCameraModel();
01944                                                         }
01945                                                         else if(_dbDriver)
01946                                                         {
01947                                                                 _dbDriver->getCalibration(iter->first, models, stereoModel);
01948                                                         }
01949 
01950 #ifdef RTABMAP_CPUTSDF
01951                                                         if(_ui->comboBox_meshingApproach->currentIndex()==2 && _ui->checkBox_assemble->isChecked())
01952                                                         {
01953                                                                 if(tsdf.get() == 0)
01954                                                                 {
01955                                                                         if(models.size()==1 && models[0].isValidForProjection() && models[0].imageHeight()>0 && models[0].imageWidth()>0)
01956                                                                         {
01957                                                                                 float tsdf_size = _ui->doubleSpinBox_cputsdf_size->value();
01958                                                                                 float cell_size = _ui->doubleSpinBox_cputsdf_resolution->value();
01959                                                                                 int num_random_splits = _ui->spinBox_cputsdf_randomSplit->value();
01960                                                                                 int tsdf_res;
01961                                                                                 int desired_res = tsdf_size / cell_size;
01962                                                                                 // Snap to nearest power of 2;
01963                                                                                 int n = 1;
01964                                                                                 while (desired_res > n)
01965                                                                                 {
01966                                                                                         n *= 2;
01967                                                                                 }
01968                                                                                 tsdf_res = n;
01969                                                                                 _progressDialog->appendText(tr("CPU-TSDF: Setting resolution: %1 with grid size %2").arg(tsdf_res).arg(tsdf_size));
01970                                                                                 tsdf.reset (new cpu_tsdf::TSDFVolumeOctree);
01971                                                                                 tsdf->setGridSize (tsdf_size, tsdf_size, tsdf_size);
01972                                                                                 tsdf->setResolution (tsdf_res, tsdf_res, tsdf_res);
01973                                                                                 float decimation = float(models[0].imageWidth()) / float(iter->second->width);
01974                                                                                 tsdf->setImageSize (models[0].imageWidth()/decimation, models[0].imageHeight()/decimation);
01975                                                                                 tsdf->setCameraIntrinsics (models[0].fx()/decimation, models[0].fy()/decimation, models[0].cx()/decimation, models[0].cy()/decimation);
01976                                                                                 tsdf->setNumRandomSplts (num_random_splits);
01977                                                                                 tsdf->setSensorDistanceBounds (0, 9999);
01978                                                                                 tsdf->setIntegrateColor(true);
01979                                                                                 tsdf->setDepthTruncationLimits (_ui->doubleSpinBox_cputsdf_tuncPos->value(), _ui->doubleSpinBox_cputsdf_tuncNeg->value());
01980                                                                                 tsdf->reset ();
01981                                                                         }
01982                                                                         else
01983                                                                         {
01984                                                                                 _progressDialog->appendText(tr("CPU-TSDF: Invalid camera model! Only single RGB-D camera supported."), Qt::darkYellow);
01985                                                                                 _progressDialog->setAutoClose(false);
01986                                                                                 break;
01987                                                                         }
01988                                                                 }
01989 
01990                                                                 if(tsdf.get())
01991                                                                 {
01992                                                                         if(tsdf.get() && models.size() == 1 && !models[0].localTransform().isNull())
01993                                                                         {
01994                                                                                 Eigen::Affine3d  pose_rel_to_first_frame = ((poses.begin()->second.inverse() * poses.at(iter->first))*models[0].localTransform()).toEigen3d();
01995                                                                                 if(!tsdf->integrateCloud(*util3d::transformPointCloud(iter->second, models[0].localTransform().inverse()), pcl::PointCloud<pcl::Normal>(), pose_rel_to_first_frame))
01996                                                                                 {
01997                                                                                         _progressDialog->appendText(tr("CPU-TSDF: Failed integrating cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
01998                                                                                 }
01999                                                                                 else
02000                                                                                 {
02001                                                                                         _progressDialog->appendText(tr("CPU-TSDF: Integrated cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
02002                                                                                 }
02003                                                                         }
02004                                                                 }
02005                                                         }
02006                                                         else
02007 #endif
02008                                                         {
02009                                                                 if((_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex() != 2) ||
02010                                                                         !iter->second->isOrganized())
02011                                                                 {
02012                                                                         if(models.size() && !models[0].localTransform().isNull())
02013                                                                         {
02014                                                                                 viewpoint[0] = models[0].localTransform().x();
02015                                                                                 viewpoint[1] = models[0].localTransform().y();
02016                                                                                 viewpoint[2] = models[0].localTransform().z();
02017                                                                         }
02018                                                                         else if(!stereoModel.localTransform().isNull())
02019                                                                         {
02020                                                                                 viewpoint[0] = stereoModel.localTransform().x();
02021                                                                                 viewpoint[1] = stereoModel.localTransform().y();
02022                                                                                 viewpoint[2] = stereoModel.localTransform().z();
02023                                                                         }
02024                                                                 }
02025 
02026                                                                 std::vector<pcl::Vertices> polygons = util3d::organizedFastMesh(
02027                                                                                 iter->second,
02028                                                                                 _ui->doubleSpinBox_mesh_angleTolerance->value()*M_PI/180.0,
02029                                                                                 _ui->checkBox_mesh_quad->isEnabled() && _ui->checkBox_mesh_quad->isChecked(),
02030                                                                                 _ui->spinBox_mesh_triangleSize->value(),
02031                                                                                 viewpoint);
02032 
02033                                                                 if(_ui->spinBox_mesh_minClusterSize->value() != 0)
02034                                                                 {
02035                                                                         _progressDialog->appendText(tr("Filter small polygon clusters..."));
02036                                                                         QApplication::processEvents();
02037 
02038                                                                         // filter polygons
02039                                                                         std::vector<std::set<int> > neighbors;
02040                                                                         std::vector<std::set<int> > vertexToPolygons;
02041                                                                         util3d::createPolygonIndexes(polygons,
02042                                                                                         (int)iter->second->size(),
02043                                                                                         neighbors,
02044                                                                                         vertexToPolygons);
02045                                                                         std::list<std::list<int> > clusters = util3d::clusterPolygons(
02046                                                                                         neighbors,
02047                                                                                         _ui->spinBox_mesh_minClusterSize->value()<0?0:_ui->spinBox_mesh_minClusterSize->value());
02048 
02049                                                                         std::vector<pcl::Vertices> filteredPolygons(polygons.size());
02050                                                                         if(_ui->spinBox_mesh_minClusterSize->value() < 0)
02051                                                                         {
02052                                                                                 // only keep the biggest cluster
02053                                                                                 std::list<std::list<int> >::iterator biggestClusterIndex = clusters.end();
02054                                                                                 unsigned int biggestClusterSize = 0;
02055                                                                                 for(std::list<std::list<int> >::iterator iter=clusters.begin(); iter!=clusters.end(); ++iter)
02056                                                                                 {
02057                                                                                         if(iter->size() > biggestClusterSize)
02058                                                                                         {
02059                                                                                                 biggestClusterIndex = iter;
02060                                                                                                 biggestClusterSize = iter->size();
02061                                                                                         }
02062                                                                                 }
02063                                                                                 if(biggestClusterIndex != clusters.end())
02064                                                                                 {
02065                                                                                         int oi=0;
02066                                                                                         for(std::list<int>::iterator jter=biggestClusterIndex->begin(); jter!=biggestClusterIndex->end(); ++jter)
02067                                                                                         {
02068                                                                                                 filteredPolygons[oi++] = polygons.at(*jter);
02069                                                                                         }
02070                                                                                         filteredPolygons.resize(oi);
02071                                                                                 }
02072                                                                         }
02073                                                                         else
02074                                                                         {
02075                                                                                 int oi=0;
02076                                                                                 for(std::list<std::list<int> >::iterator iter=clusters.begin(); iter!=clusters.end(); ++iter)
02077                                                                                 {
02078                                                                                         for(std::list<int>::iterator jter=iter->begin(); jter!=iter->end(); ++jter)
02079                                                                                         {
02080                                                                                                 filteredPolygons[oi++] = polygons.at(*jter);
02081                                                                                         }
02082                                                                                 }
02083                                                                                 filteredPolygons.resize(oi);
02084                                                                         }
02085                                                                         int before = (int)polygons.size();
02086                                                                         polygons = filteredPolygons;
02087 
02088                                                                         if(polygons.size() == 0)
02089                                                                         {
02090                                                                                 std::string msg = uFormat("All %d polygons filtered after polygon cluster filtering. Cluster minimum size is %d.", before, _ui->spinBox_mesh_minClusterSize->value());
02091                                                                                 _progressDialog->appendText(msg.c_str(), Qt::darkYellow);
02092                                                                                 UWARN(msg.c_str());
02093                                                                         }
02094 
02095                                                                         _progressDialog->appendText(tr("Filtered %1 polygons.").arg(before-(int)polygons.size()));
02096                                                                         QApplication::processEvents();
02097                                                                 }
02098 
02099                                                                 _progressDialog->appendText(tr("Mesh %1 created with %2 polygons (%3/%4).").arg(iter->first).arg(polygons.size()).arg(cloudsAdded).arg(cloudsWithNormals.size()));
02100 
02101                                                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr denseCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
02102                                                                 std::vector<pcl::Vertices> densePolygons;
02103                                                                 std::vector<int> denseToOrganizedIndices = util3d::filterNotUsedVerticesFromMesh(*iter->second, polygons, *denseCloud, densePolygons);
02104 
02105                                                                 if(!_ui->checkBox_assemble->isChecked() ||
02106                                                                          (_ui->checkBox_textureMapping->isEnabled() &&
02107                                                                           _ui->checkBox_textureMapping->isChecked() &&
02108                                                                           _ui->doubleSpinBox_voxelSize_assembled->value() == 0.0)) // don't assemble now if we are texturing
02109                                                                 {
02110                                                                         if(_ui->checkBox_assemble->isChecked())
02111                                                                         {
02112                                                                                 denseCloud = util3d::transformPointCloud(denseCloud, poses.at(iter->first));
02113                                                                         }
02114 
02115                                                                         pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
02116                                                                         pcl::toPCLPointCloud2(*denseCloud, mesh->cloud);
02117                                                                         mesh->polygons = densePolygons;
02118 
02119                                                                         organizedIndices.insert(std::make_pair(iter->first, denseToOrganizedIndices));
02120                                                                         organizedCloudSizes.insert(std::make_pair(iter->first, cv::Size(iter->second->width, iter->second->height)));
02121 
02122                                                                         meshes.insert(std::make_pair(iter->first, mesh));
02123                                                                 }
02124                                                                 else
02125                                                                 {
02126                                                                         denseCloud = util3d::transformPointCloud(denseCloud, poses.at(iter->first));
02127                                                                         if(mergedClouds->size() == 0)
02128                                                                         {
02129                                                                                 *mergedClouds = *denseCloud;
02130                                                                                 mergedPolygons = densePolygons;
02131                                                                         }
02132                                                                         else
02133                                                                         {
02134                                                                                 util3d::appendMesh(*mergedClouds, mergedPolygons, *denseCloud, densePolygons);
02135                                                                         }
02136                                                                 }
02137                                                         }
02138                                                 }
02139                                                 else
02140                                                 {
02141                                                         _progressDialog->appendText(tr("Mesh %1 not created (no valid points) (%2/%3).").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
02142                                                 }
02143                                         }
02144                                         else
02145                                         {
02146                                                 int weight = 0;
02147                                                 if(cachedSignatures.contains(iter->first))
02148                                                 {
02149                                                         const Signature & s = cachedSignatures.find(iter->first).value();
02150                                                         weight = s.getWeight();
02151                                                 }
02152                                                 else if(_dbDriver)
02153                                                 {
02154                                                         _dbDriver->getWeight(iter->first, weight);
02155                                                 }
02156                                                 if(weight>=0) // don't show error for intermediate nodes
02157                                                 {
02158                                                         _progressDialog->appendText(tr("Mesh %1 not created (cloud is not organized). You may want to check cloud regeneration option (%2/%3).").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
02159                                                 }
02160                                         }
02161 
02162                                         _progressDialog->incrementStep();
02163                                         QApplication::processEvents();
02164                                         if(_canceled)
02165                                         {
02166                                                 return false;
02167                                         }
02168                                 }
02169 
02170                                 if(_ui->checkBox_assemble->isChecked() && mergedClouds->size())
02171                                 {
02172                                         if(_ui->doubleSpinBox_voxelSize_assembled->value())
02173                                         {
02174                                                 _progressDialog->appendText(tr("Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").arg(mergedClouds->size()).arg(mergedPolygons.size()));
02175                                                 QApplication::processEvents();
02176 
02177                                                 mergedPolygons = util3d::filterCloseVerticesFromMesh(
02178                                                                 mergedClouds,
02179                                                                 mergedPolygons,
02180                                                                 _ui->doubleSpinBox_voxelSize_assembled->value(),
02181                                                                 M_PI/4,
02182                                                                 true);
02183 
02184                                                 // filter invalid polygons
02185                                                 unsigned int count = mergedPolygons.size();
02186                                                 mergedPolygons = util3d::filterInvalidPolygons(mergedPolygons);
02187                                                 _progressDialog->appendText(tr("Filtered %1 invalid polygons.").arg(count-mergedPolygons.size()));
02188                                                 QApplication::processEvents();
02189 
02190                                                 // filter not used vertices
02191                                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
02192                                                 std::vector<pcl::Vertices> filteredPolygons;
02193                                                 util3d::filterNotUsedVerticesFromMesh(*mergedClouds, mergedPolygons, *filteredCloud, filteredPolygons);
02194                                                 mergedClouds = filteredCloud;
02195                                                 mergedPolygons = filteredPolygons;
02196                                         }
02197 
02198                                         pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
02199                                         pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
02200                                         mesh->polygons = mergedPolygons;
02201 
02202                                         meshes.insert(std::make_pair(0, mesh));
02203 
02204                                         _progressDialog->incrementStep();
02205                                         QApplication::processEvents();
02206                                 }
02207                         }
02208                         else // dense pipeline
02209                         {
02210                                 if(_ui->comboBox_meshingApproach->currentIndex() == 0)
02211                                 {
02212                                         _progressDialog->appendText(tr("Greedy projection triangulation... [radius=%1m]").arg(_ui->doubleSpinBox_gp3Radius->value()));
02213                                 }
02214                                 else
02215                                 {
02216                                         _progressDialog->appendText(tr("Poisson surface reconstruction..."));
02217                                 }
02218                                 QApplication::processEvents();
02219                                 uSleep(100);
02220                                 QApplication::processEvents();
02221 
02222                                 int cloudsAdded=1;
02223                                 for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::iterator iter=cloudsWithNormals.begin();
02224                                         iter!= cloudsWithNormals.end();
02225                                         ++iter,++cloudsAdded)
02226                                 {
02227                                         pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
02228                                         if(_ui->comboBox_meshingApproach->currentIndex() == 0)
02229                                         {
02230                                                 mesh = util3d::createMesh(
02231                                                                 iter->second,
02232                                                                 _ui->doubleSpinBox_gp3Radius->value(),
02233                                                                 _ui->doubleSpinBox_gp3Mu->value());
02234                                         }
02235                                         else
02236                                         {
02237                                                 pcl::Poisson<pcl::PointXYZRGBNormal> poisson;
02238                                                 poisson.setOutputPolygons(_ui->checkBox_poisson_outputPolygons->isEnabled()?_ui->checkBox_poisson_outputPolygons->isChecked():false);
02239                                                 poisson.setManifold(_ui->checkBox_poisson_manifold->isChecked());
02240                                                 poisson.setSamplesPerNode(_ui->doubleSpinBox_poisson_samples->value());
02241                                                 int depth = _ui->spinBox_poisson_depth->value();
02242                                                 if(depth == 0)
02243                                                 {
02244                                                         Eigen::Vector4f min,max;
02245                                                         pcl::getMinMax3D(*iter->second, min, max);
02246                                                         float mapLength = uMax3(max[0]-min[0], max[1]-min[1], max[2]-min[2]);
02247                                                         depth = 12;
02248                                                         for(int i=6; i<12; ++i)
02249                                                         {
02250                                                                 if(mapLength/float(1<<i) < 0.03f)
02251                                                                 {
02252                                                                         depth = i;
02253                                                                         break;
02254                                                                 }
02255                                                         }
02256                                                         _progressDialog->appendText(tr("Poisson depth resolution chosen is %1, map size (m) = %2x%3x%4")
02257                                                                         .arg(depth)
02258                                                                         .arg(int(max[0]-min[0]))
02259                                                                         .arg(int(max[1]-min[1]))
02260                                                                         .arg(int(max[2]-min[2])));
02261                                                         QApplication::processEvents();
02262                                                         uSleep(100);
02263                                                         QApplication::processEvents();
02264                                                 }
02265                                                 poisson.setDepth(depth);
02266                                                 poisson.setIsoDivide(_ui->spinBox_poisson_iso->value());
02267                                                 poisson.setSolverDivide(_ui->spinBox_poisson_solver->value());
02268                                                 poisson.setMinDepth(_ui->spinBox_poisson_minDepth->value());
02269                                                 poisson.setPointWeight(_ui->doubleSpinBox_poisson_pointWeight->value());
02270                                                 poisson.setScale(_ui->doubleSpinBox_poisson_scale->value());
02271                                                 poisson.setInputCloud(iter->second);
02272                                                 poisson.reconstruct(*mesh);
02273                                         }
02274 
02275                                         _progressDialog->appendText(tr("Mesh %1 created with %2 polygons (%3/%4).").arg(iter->first).arg(mesh->polygons.size()).arg(cloudsAdded).arg(cloudsWithNormals.size()));
02276                                         QApplication::processEvents();
02277 
02278                                         if(mesh->polygons.size()>0)
02279                                         {
02280                                                 TexturingState texturingState(_progressDialog, false);
02281                                                 util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
02282                                                                 mesh,
02283                                                                 _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
02284                                                                 _ui->spinBox_meshMaxPolygons->isEnabled()?_ui->spinBox_meshMaxPolygons->value():0,
02285                                                                 iter->second,
02286                                                                 (float)_ui->doubleSpinBox_transferColorRadius->value(),
02287                                                                 !(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()),
02288                                                                 _ui->checkBox_cleanMesh->isChecked(),
02289                                                                 _ui->spinBox_mesh_minClusterSize->value(),
02290                                                                 &texturingState);
02291                                                 meshes.insert(std::make_pair(iter->first, mesh));
02292                                         }
02293                                         else
02294                                         {
02295                                                 _progressDialog->appendText(tr("No polygons created for cloud %d!").arg(iter->first), Qt::darkYellow);
02296                                                 _progressDialog->setAutoClose(false);
02297                                         }
02298 
02299                                         _progressDialog->incrementStep(_ui->checkBox_assemble->isChecked()?poses.size():1);
02300                                         QApplication::processEvents();
02301                                         if(_canceled)
02302                                         {
02303                                                 return false;
02304                                         }
02305                                 }
02306                         }
02307                 }
02308                 else if(_ui->checkBox_meshing->isChecked())
02309                 {
02310                         std::string msg = uFormat("Some clouds are 2D laser scans. Meshing can be done only from RGB-D clouds or 3D laser scans.");
02311                         _progressDialog->appendText(msg.c_str(), Qt::darkYellow);
02312                         UWARN(msg.c_str());
02313                 }
02314 
02315                 UDEBUG("");
02316 #ifdef RTABMAP_CPUTSDF
02317                 if(tsdf.get())
02318                 {
02319                         _progressDialog->appendText(tr("CPU-TSDF: Creating mesh from TSDF volume..."));
02320                         QApplication::processEvents();
02321                         uSleep(100);
02322                         QApplication::processEvents();
02323 
02324                         cpu_tsdf::MarchingCubesTSDFOctree mc;
02325                         mc.setMinWeight (_ui->doubleSpinBox_cputsdf_minWeight->value());
02326                         mc.setInputTSDF (tsdf);
02327                         mc.setColorByRGB (true);
02328                         pcl::PolygonMesh::Ptr mesh (new pcl::PolygonMesh);
02329                         mc.reconstruct (*mesh);
02330                         _progressDialog->appendText(tr("CPU-TSDF: Creating mesh from TSDF volume...done! %1 polygons").arg(mesh->polygons.size()));
02331                         meshes.clear();
02332 
02333                         if(mesh->polygons.size()>0)
02334                         {
02335 
02336                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr vertices (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
02337                                 pcl::fromPCLPointCloud2 (mesh->cloud, *vertices);
02338 
02339                                 if(_ui->doubleSpinBox_cputsdf_flattenRadius->value()>0.0)
02340                                 {
02341                                         _progressDialog->appendText(tr("CPU-TSDF: Flattening mesh (radius=%1)...").arg(_ui->doubleSpinBox_cputsdf_flattenRadius->value()));
02342                                         QApplication::processEvents();
02343                                         uSleep(100);
02344                                         QApplication::processEvents();
02345 
02346                                         float min_dist = _ui->doubleSpinBox_cputsdf_flattenRadius->value();
02347                                         pcl::search::KdTree<pcl::PointXYZRGBNormal> vert_tree (true);
02348                                         vert_tree.setInputCloud (vertices);
02349                                         // Find duplicates
02350                                         std::vector<int> vertex_remap (vertices->size (), -1);
02351                                         int idx = 0;
02352                                         std::vector<int> neighbors;
02353                                         std::vector<float> dists;
02354                                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr vertices_new(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
02355                                         vertices_new->resize(vertices->size ());
02356                                         for (size_t i = 0; i < vertices->size (); i++)
02357                                         {
02358                                                 if (vertex_remap[i] >= 0)
02359                                                         continue;
02360                                                 vertex_remap[i] = idx;
02361                                                 vert_tree.radiusSearch (i, min_dist, neighbors, dists);
02362                                                 for (size_t j = 1; j < neighbors.size (); j++)
02363                                                 {
02364                                                         if (dists[j] < min_dist)
02365                                                                 vertex_remap[neighbors[j]] = idx;
02366                                                 }
02367                                                 vertices_new->at(idx++) = vertices->at (i);
02368                                         }
02369                                         vertices_new->resize(idx);
02370                                         std::vector<size_t> faces_to_remove;
02371                                         size_t face_idx = 0;
02372                                         for (size_t i = 0; i < mesh->polygons.size (); i++)
02373                                         {
02374                                                 pcl::Vertices &v = mesh->polygons[i];
02375                                                 for (size_t j = 0; j < v.vertices.size (); j++)
02376                                                 {
02377                                                         v.vertices[j] = vertex_remap[v.vertices[j]];
02378                                                 }
02379                                                 if (!(v.vertices[0] == v.vertices[1] || v.vertices[1] == v.vertices[2] || v.vertices[2] == v.vertices[0]))
02380                                                 {
02381                                                         mesh->polygons[face_idx++] = mesh->polygons[i];
02382                                                 }
02383                                         }
02384                                         mesh->polygons.resize (face_idx);
02385                                         pcl::toPCLPointCloud2 (*vertices_new, mesh->cloud);
02386                                         vertices = vertices_new;
02387                                 }
02388 
02389                                 pcl::fromPCLPointCloud2(mesh->cloud, *vertices);
02390                                 TexturingState texturingState(_progressDialog, false);
02391                                 util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
02392                                                 mesh,
02393                                                 _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
02394                                                 _ui->spinBox_meshMaxPolygons->isEnabled()?_ui->spinBox_meshMaxPolygons->value():0,
02395                                                 vertices,
02396                                                 (float)_ui->doubleSpinBox_transferColorRadius->value(),
02397                                                 !(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()),
02398                                                 _ui->checkBox_cleanMesh->isChecked(),
02399                                                 _ui->spinBox_mesh_minClusterSize->value(),
02400                                                 &texturingState);
02401                                 meshes.insert(std::make_pair(0, mesh));
02402                         }
02403                         else
02404                         {
02405                                 _progressDialog->appendText(tr("No polygons created TSDF volume!"), Qt::darkYellow);
02406                                 _progressDialog->setAutoClose(false);
02407                         }
02408                 }
02409 #endif
02410 #ifdef RTABMAP_OPENCHISEL
02411                 if(chiselMap.get())
02412                 {
02413                         _progressDialog->appendText(tr("OpenChisel: Creating mesh from TSDF volume..."));
02414                         QApplication::processEvents();
02415                         uSleep(100);
02416                         QApplication::processEvents();
02417 
02418                         const chisel::MeshMap& meshMap = chiselMap->GetChunkManager().GetAllMeshes();
02419                         pcl::PolygonMesh::Ptr mesh = chiselToPolygonMesh(meshMap);
02420 
02421                         // To debug...
02422                         //std::string filePly = _workingDirectory.toStdString()+"/"+"chisel.ply";
02423                         //chiselMap->SaveAllMeshesToPLY(filePly);
02424                         //UWARN("Saved %s", filePly.c_str());
02425 
02426                         _progressDialog->appendText(tr("OpenChisel: Creating mesh from TSDF volume...done! %1 polygons").arg(mesh->polygons.size()));
02427 
02428                         meshes.clear();
02429                         if(mesh->polygons.size()>0)
02430                         {
02431                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
02432                                 pcl::fromPCLPointCloud2(mesh->cloud, *mergedClouds);
02433                                 if(_ui->checkBox_openchisel_mergeVertices->isChecked())
02434                                 {
02435                                         _progressDialog->appendText(tr("Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").arg(mergedClouds->size()).arg(mesh->polygons.size()));
02436                                         QApplication::processEvents();
02437 
02438                                         mesh->polygons = util3d::filterCloseVerticesFromMesh(
02439                                                         mergedClouds,
02440                                                         mesh->polygons,
02441                                                         _ui->doubleSpinBox_voxelSize_assembled->value()/2.0,
02442                                                         M_PI/4,
02443                                                         true);
02444 
02445                                         // filter invalid polygons
02446                                         unsigned int count = mesh->polygons.size();
02447                                         mesh->polygons = util3d::filterInvalidPolygons(mesh->polygons);
02448                                         _progressDialog->appendText(tr("Filtered %1 invalid polygons.").arg(count-mesh->polygons.size()));
02449                                         QApplication::processEvents();
02450 
02451                                         // filter not used vertices
02452                                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
02453                                         std::vector<pcl::Vertices> filteredPolygons;
02454                                         count = mergedClouds->size();
02455                                         util3d::filterNotUsedVerticesFromMesh(*mergedClouds, mesh->polygons, *filteredCloud, filteredPolygons);
02456                                         mergedClouds = filteredCloud;
02457                                         pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
02458                                         mesh->polygons = filteredPolygons;
02459                                         _progressDialog->appendText(tr("Filtered %1 duplicate vertices.").arg(count-mergedClouds->size()));
02460                                         QApplication::processEvents();
02461                                 }
02462                                 TexturingState texturingState(_progressDialog, false);
02463                                 util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
02464                                                 mesh,
02465                                                 _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
02466                                                 _ui->spinBox_meshMaxPolygons->isEnabled()?_ui->spinBox_meshMaxPolygons->value():0,
02467                                                 mergedClouds,
02468                                                 (float)_ui->doubleSpinBox_transferColorRadius->value(),
02469                                                 !(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()),
02470                                                 _ui->checkBox_cleanMesh->isChecked(),
02471                                                 _ui->spinBox_mesh_minClusterSize->value(),
02472                                                 &texturingState);
02473                                 meshes.insert(std::make_pair(0, mesh));
02474                         }
02475                         else
02476                         {
02477                                 _progressDialog->appendText(tr("No polygons created TSDF volume!"), Qt::darkYellow);
02478                                 _progressDialog->setAutoClose(false);
02479                         }
02480                 }
02481 #endif
02482 
02483                 UDEBUG("");
02484                 if(_canceled)
02485                 {
02486                         return false;
02487                 }
02488 
02489                 // texture mesh
02490                 UDEBUG("texture mapping=%d", _ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()?1:0);
02491                 if(!has2dScans && _ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked())
02492                 {
02493                         _progressDialog->appendText(tr("Texturing..."));
02494                         QApplication::processEvents();
02495                         uSleep(100);
02496                         QApplication::processEvents();
02497 
02498                         int i=0;
02499                         for(std::map<int, pcl::PolygonMesh::Ptr>::iterator iter=meshes.begin();
02500                                 iter!= meshes.end();
02501                                 ++iter)
02502                         {
02503                                 std::map<int, Transform> cameras;
02504                                 if(iter->first == 0)
02505                                 {
02506                                         cameras = poses;
02507                                 }
02508                                 else
02509                                 {
02510                                         UASSERT(uContains(poses, iter->first));
02511                                         cameras.insert(std::make_pair(iter->first, _ui->checkBox_assemble->isChecked()?poses.at(iter->first):Transform::getIdentity()));
02512                                 }
02513                                 std::map<int, Transform> cameraPoses;
02514                                 std::map<int, std::vector<CameraModel> > cameraModels;
02515                                 std::map<int, cv::Mat > cameraDepths;
02516                                 int ignoredCameras = 0;
02517                                 for(std::map<int, Transform>::iterator jter=cameras.begin(); jter!=cameras.end(); ++jter)
02518                                 {
02519                                         if(validCameras.find(jter->first) != validCameras.end())
02520                                         {
02521                                                 std::vector<CameraModel> models;
02522                                                 StereoCameraModel stereoModel;
02523                                                 bool cacheHasCompressedImage = false;
02524                                                 if(cachedSignatures.contains(jter->first))
02525                                                 {
02526                                                         const SensorData & data = cachedSignatures.find(jter->first)->sensorData();
02527                                                         models = data.cameraModels();
02528                                                         stereoModel = data.stereoCameraModel();
02529                                                         cacheHasCompressedImage = !data.imageCompressed().empty();
02530                                                 }
02531                                                 else if(_dbDriver)
02532                                                 {
02533                                                         _dbDriver->getCalibration(jter->first, models, stereoModel);
02534                                                 }
02535 
02536                                                 bool stereo=false;
02537                                                 if(stereoModel.isValidForProjection())
02538                                                 {
02539                                                         stereo = true;
02540                                                         models.clear();
02541                                                         models.push_back(stereoModel.left());
02542                                                 }
02543                                                 else if(models.size() == 0 || !models[0].isValidForProjection())
02544                                                 {
02545                                                         models.clear();
02546                                                 }
02547 
02548                                                 if(!jter->second.isNull() && models.size())
02549                                                 {
02550                                                         cv::Mat depth;
02551                                                         bool blurryImage = false;
02552                                                         bool getDepth = !stereo && _ui->doubleSpinBox_meshingTextureMaxDepthError->value() >= 0.0f;
02553                                                         cv::Mat img;
02554                                                         std::vector<float> velocity;
02555                                                         if(models[0].imageWidth() == 0 || models[0].imageHeight() == 0)
02556                                                         {
02557                                                                 // we are using an old database format (image size not saved in calibrations), we should
02558                                                                 // uncompress images to get their size
02559                                                                 if(cacheHasCompressedImage)
02560                                                                 {
02561                                                                         cachedSignatures.find(jter->first)->sensorData().uncompressDataConst(&img, getDepth?&depth:0);
02562                                                                         velocity = cachedSignatures.find(jter->first)->getVelocity();
02563                                                                 }
02564                                                                 else if(_dbDriver)
02565                                                                 {
02566                                                                         SensorData data;
02567                                                                         _dbDriver->getNodeData(jter->first, data, true, false, false, false);
02568                                                                         data.uncompressDataConst(&img, getDepth?&depth:0);
02569 
02570                                                                         if(_ui->checkBox_cameraFilter->isChecked() &&
02571                                                                                 (_ui->doubleSpinBox_cameraFilterVel->value()>0.0 || _ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
02572                                                                         {
02573                                                                                 Transform p,gt;
02574                                                                                 int m,w;
02575                                                                                 std::string l;
02576                                                                                 double s;
02577                                                                                 GPS gps;
02578                                                                                 _dbDriver->getNodeInfo(jter->first, p, m, w, l, s, gt, velocity, gps);
02579                                                                         }
02580                                                                 }
02581                                                                 cv::Size imageSize = img.size();
02582                                                                 imageSize.width /= models.size();
02583                                                                 for(unsigned int i=0; i<models.size(); ++i)
02584                                                                 {
02585                                                                         models[i].setImageSize(imageSize);
02586                                                                 }
02587                                                         }
02588                                                         else
02589                                                         {
02590                                                                 bool getImg = _ui->checkBox_cameraFilter->isChecked() && _ui->doubleSpinBox_laplacianVariance->value()>0.0;
02591                                                                 // get just the depth
02592                                                                 if(cacheHasCompressedImage)
02593                                                                 {
02594                                                                         cachedSignatures.find(jter->first)->sensorData().uncompressDataConst(getImg?&img:0, getDepth?&depth:0);
02595                                                                         velocity = cachedSignatures.find(jter->first)->getVelocity();
02596                                                                 }
02597                                                                 else if(_dbDriver)
02598                                                                 {
02599                                                                         SensorData data;
02600                                                                         _dbDriver->getNodeData(jter->first, data, true, false, false, false);
02601                                                                         data.uncompressDataConst(getImg?&img:0, getDepth?&depth:0);
02602 
02603                                                                         if(_ui->checkBox_cameraFilter->isChecked() &&
02604                                                                                 (_ui->doubleSpinBox_cameraFilterVel->value()>0.0 || _ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
02605                                                                         {
02606                                                                                 Transform p,gt;
02607                                                                                 int m,w;
02608                                                                                 std::string l;
02609                                                                                 double s;
02610                                                                                 GPS gps;
02611                                                                                 _dbDriver->getNodeInfo(jter->first, p, m, w, l, s, gt, velocity, gps);
02612                                                                         }
02613                                                                 }
02614                                                         }
02615                                                         if(_ui->checkBox_cameraFilter->isChecked())
02616                                                         {
02617                                                                 std::string msg;
02618                                                                 if(!blurryImage &&
02619                                                                         (_ui->doubleSpinBox_cameraFilterVel->value()>0.0 || _ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
02620                                                                 {
02621                                                                         if(velocity.size() == 6)
02622                                                                         {
02623                                                                                 float transVel = uMax3(fabs(velocity[0]), fabs(velocity[1]), fabs(velocity[2]));
02624                                                                                 float rotVel = uMax3(fabs(velocity[3]), fabs(velocity[4]), fabs(velocity[5]));
02625                                                                                 if(_ui->doubleSpinBox_cameraFilterVel->value()>0.0 && transVel > _ui->doubleSpinBox_cameraFilterVel->value())
02626                                                                                 {
02627                                                                                         msg = uFormat("Fast motion detected for camera %d (speed=%f m/s > thr=%f m/s), camera is ignored for texturing.", jter->first, transVel, _ui->doubleSpinBox_cameraFilterVel->value());
02628                                                                                         blurryImage = true;
02629                                                                                 }
02630                                                                                 else if(_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0 && rotVel > _ui->doubleSpinBox_cameraFilterVelRad->value())
02631                                                                                 {
02632                                                                                         msg = uFormat("Fast motion detected for camera %d (speed=%f rad/s > thr=%f rad/s), camera is ignored for texturing.", jter->first, rotVel, _ui->doubleSpinBox_cameraFilterVelRad->value());
02633                                                                                         blurryImage = true;
02634                                                                                 }
02635                                                                         }
02636                                                                         else
02637                                                                         {
02638                                                                                 UWARN("Camera motion filtering is set, but velocity of camera %d is not available.", jter->first);
02639                                                                         }
02640                                                                 }
02641 
02642                                                                 if(!blurryImage && !img.empty() && _ui->doubleSpinBox_laplacianVariance->value()>0.0)
02643                                                                 {
02644                                                                         cv::Mat imgLaplacian;
02645                                                                         cv::Laplacian(img, imgLaplacian, CV_16S);
02646                                                                         cv::Mat m, s;
02647                                                                         cv::meanStdDev(imgLaplacian, m, s);
02648                                                                         double stddev_pxl = s.at<double>(0);
02649                                                                         double var = stddev_pxl*stddev_pxl;
02650                                                                         if(var < _ui->doubleSpinBox_laplacianVariance->value())
02651                                                                         {
02652                                                                                 blurryImage = true;
02653                                                                                 msg = uFormat("Camera's image %d is detected as blurry (var=%f < thr=%f), camera is ignored for texturing.", jter->first, var, _ui->doubleSpinBox_laplacianVariance->value());
02654                                                                         }
02655                                                                 }
02656                                                                 if(blurryImage)
02657                                                                 {
02658                                                                         _progressDialog->appendText(msg.c_str());
02659                                                                         QApplication::processEvents();
02660                                                                         ++ignoredCameras;
02661                                                                 }
02662                                                         }
02663 
02664                                                         if(!blurryImage && models[0].imageWidth() != 0 && models[0].imageHeight() != 0)
02665                                                         {
02666                                                                 cameraPoses.insert(std::make_pair(jter->first, jter->second));
02667                                                                 cameraModels.insert(std::make_pair(jter->first, models));
02668                                                                 if(!depth.empty())
02669                                                                 {
02670                                                                         cameraDepths.insert(std::make_pair(jter->first, depth));
02671                                                                 }
02672                                                         }
02673                                                 }
02674                                         }
02675                                 }
02676                                 if(ignoredCameras > (int)validCameras.size()/2)
02677                                 {
02678                                         std::string msg = uFormat("More than 50%% of the cameras (%d/%d) have been filtered for "
02679                                                         "too fast motion and/or blur level. You may adjust the corresponding thresholds.",
02680                                                         ignoredCameras, (int)validCameras.size());
02681                                         UWARN(msg.c_str());
02682                                         _progressDialog->appendText(msg.c_str(), Qt::darkYellow);
02683                                         _progressDialog->setAutoClose(false);
02684                                         QApplication::processEvents();
02685                                 }
02686 
02687                                 if(cameraPoses.size() && iter->second->polygons.size())
02688                                 {
02689                                         pcl::TextureMesh::Ptr textureMesh(new pcl::TextureMesh);
02690                                         std::map<int, std::vector<int> >::iterator oter = organizedIndices.find(iter->first);
02691                                         std::map<int, cv::Size>::iterator ster = organizedCloudSizes.find(iter->first);
02692                                         if(iter->first != 0 && oter != organizedIndices.end())
02693                                         {
02694                                                 UASSERT(ster!=organizedCloudSizes.end()&&ster->first == oter->first);
02695                                                 UDEBUG("Texture by pixels");
02696                                                 textureMesh->cloud = iter->second->cloud;
02697                                                 textureMesh->tex_polygons.push_back(iter->second->polygons);
02698                                                 int w = ster->second.width;
02699                                                 int h = ster->second.height;
02700                                                 UASSERT(w > 1 && h > 1);
02701                                                 if(textureMesh->tex_polygons.size() && textureMesh->tex_polygons[0].size())
02702                                                 {
02703                                                         textureMesh->tex_coordinates.resize(1);
02704 
02705                                                         //tex_coordinates should be linked to polygon vertices
02706                                                         int polygonSize = (int)textureMesh->tex_polygons[0][0].vertices.size();
02707                                                         textureMesh->tex_coordinates[0].resize(polygonSize*textureMesh->tex_polygons[0].size());
02708                                                         for(unsigned int i=0; i<textureMesh->tex_polygons[0].size(); ++i)
02709                                                         {
02710                                                                 const pcl::Vertices & vertices = textureMesh->tex_polygons[0][i];
02711                                                                 UASSERT(polygonSize == (int)vertices.vertices.size());
02712                                                                 for(int k=0; k<polygonSize; ++k)
02713                                                                 {
02714                                                                         //uv
02715                                                                         UASSERT(vertices.vertices[k] < oter->second.size());
02716                                                                         int originalVertex = oter->second[vertices.vertices[k]];
02717                                                                         textureMesh->tex_coordinates[0][i*polygonSize+k] = Eigen::Vector2f(
02718                                                                                         float(originalVertex % w) / float(w),      // u
02719                                                                                         float(h - originalVertex / w) / float(h)); // v
02720                                                                 }
02721                                                         }
02722 
02723                                                         pcl::TexMaterial mesh_material;
02724                                                         mesh_material.tex_d = 1.0f;
02725                                                         mesh_material.tex_Ns = 75.0f;
02726                                                         mesh_material.tex_illum = 1;
02727 
02728                                                         std::stringstream tex_name;
02729                                                         tex_name << "material_" << iter->first;
02730                                                         tex_name >> mesh_material.tex_name;
02731 
02732                                                         mesh_material.tex_file = uFormat("%d", iter->first);
02733                                                         textureMesh->tex_materials.push_back(mesh_material);
02734                                                 }
02735                                                 else
02736                                                 {
02737                                                         UWARN("No polygons for mesh %d!?", iter->first);
02738                                                 }
02739                                         }
02740                                         else
02741                                         {
02742                                                 UDEBUG("Texture by projection");
02743 
02744                                                 if(cameraPoses.size() && _ui->checkBox_cameraFilter->isChecked())
02745                                                 {
02746                                                         int before = (int)cameraPoses.size();
02747                                                         cameraPoses = graph::radiusPosesFiltering(cameraPoses,
02748                                                                         _ui->doubleSpinBox_cameraFilterRadius->value(),
02749                                                                         _ui->doubleSpinBox_cameraFilterAngle->value());
02750                                                         for(std::map<int, std::vector<CameraModel> >::iterator modelIter = cameraModels.begin(); modelIter!=cameraModels.end();)
02751                                                         {
02752                                                                 if(cameraPoses.find(modelIter->first)==cameraPoses.end())
02753                                                                 {
02754                                                                         cameraModels.erase(modelIter++);
02755                                                                         cameraDepths.erase(modelIter->first);
02756                                                                 }
02757                                                                 else
02758                                                                 {
02759                                                                         ++modelIter;
02760                                                                 }
02761                                                         }
02762                                                         _progressDialog->appendText(tr("Camera filtering: keeping %1/%2 cameras for texturing.").arg(cameraPoses.size()).arg(before));
02763                                                         QApplication::processEvents();
02764                                                         uSleep(100);
02765                                                         QApplication::processEvents();
02766                                                 }
02767 
02768                                                 if(_canceled)
02769                                                 {
02770                                                         return false;
02771                                                 }
02772 
02773                                                 TexturingState texturingState(_progressDialog, true);
02774                                                 _progressDialog->setMaximumSteps(_progressDialog->maximumSteps()+iter->second->polygons.size()/10000+1);
02775                                                 if(cameraModels.size() && cameraModels.begin()->second.size()>1)
02776                                                 {
02777                                                         _progressDialog->setMaximumSteps(_progressDialog->maximumSteps()+cameraModels.size()*(cameraModels.begin()->second.size()-1));
02778                                                 }
02779 
02780                                                 std::vector<float> roiRatios;
02781                                                 QStringList strings = _ui->lineEdit_meshingTextureRoiRatios->text().split(' ');
02782                                                 if(!_ui->lineEdit_meshingTextureRoiRatios->text().isEmpty())
02783                                                 {
02784                                                         if(strings.size()==4)
02785                                                         {
02786                                                                 roiRatios.resize(4);
02787                                                                 roiRatios[0]=strings[0].toDouble();
02788                                                                 roiRatios[1]=strings[1].toDouble();
02789                                                                 roiRatios[2]=strings[2].toDouble();
02790                                                                 roiRatios[3]=strings[3].toDouble();
02791                                                                 if(!(roiRatios[0]>=0.0f && roiRatios[0]<=1.0f &&
02792                                                                         roiRatios[1]>=0.0f && roiRatios[1]<=1.0f &&
02793                                                                         roiRatios[2]>=0.0f && roiRatios[2]<=1.0f &&
02794                                                                         roiRatios[3]>=0.0f && roiRatios[3]<=1.0f))
02795                                                                 {
02796                                                                         roiRatios.clear();
02797                                                                 }
02798                                                         }
02799                                                         if(roiRatios.empty())
02800                                                         {
02801                                                                 QString msg = tr("Wrong ROI format. Region of Interest (ROI) must have 4 values [left right top bottom] between 0 and 1 separated by space (%1), ignoring it for texturing...").arg(_ui->lineEdit_meshingTextureRoiRatios->text());
02802                                                                 UWARN(msg.toStdString().c_str());
02803                                                                 _progressDialog->appendText(msg, Qt::darkYellow);
02804                                                                 _progressDialog->setAutoClose(false);
02805                                                         }
02806                                                 }
02807 
02808                                                 textureMesh = util3d::createTextureMesh(
02809                                                                 iter->second,
02810                                                                 cameraPoses,
02811                                                                 cameraModels,
02812                                                                 cameraDepths,
02813                                                                 _ui->doubleSpinBox_meshingTextureMaxDistance->value(),
02814                                                                 _ui->doubleSpinBox_meshingTextureMaxDepthError->value(),
02815                                                                 _ui->doubleSpinBox_meshingTextureMaxAngle->value()*M_PI/180.0,
02816                                                                 _ui->spinBox_mesh_minTextureClusterSize->value(),
02817                                                                 roiRatios,
02818                                                                 &texturingState,
02819                                                                 cameraPoses.size()>1?&textureVertexToPixels:0); // only get vertexToPixels if merged clouds with multi textures
02820 
02821                                                 if(_canceled)
02822                                                 {
02823                                                         return false;
02824                                                 }
02825 
02826                                                 // Remove occluded polygons (polygons with no texture)
02827                                                 if(_ui->checkBox_cleanMesh->isChecked())
02828                                                 {
02829                                                         unsigned int totalSize = 0;
02830                                                         for(unsigned int t=0; t<textureMesh->tex_polygons.size(); ++t)
02831                                                         {
02832                                                                 totalSize+=textureMesh->tex_polygons[t].size();
02833                                                         }
02834 
02835                                                         util3d::cleanTextureMesh(*textureMesh, _ui->spinBox_mesh_minClusterSize->value());
02836 
02837                                                         unsigned int totalSizeAfter = 0;
02838                                                         for(unsigned int t=0; t<textureMesh->tex_polygons.size(); ++t)
02839                                                         {
02840                                                                 totalSizeAfter+=textureMesh->tex_polygons[t].size();
02841                                                         }
02842                                                         _progressDialog->appendText(tr("Cleaned texture mesh: %1 -> %2 polygons").arg(totalSize).arg(totalSizeAfter));
02843                                                 }
02844                                         }
02845 
02846                                         textureMeshes.insert(std::make_pair(iter->first, textureMesh));
02847                                 }
02848                                 else if(cameraPoses.size() == 0)
02849                                 {
02850                                         _progressDialog->appendText(tr("No cameras from %1 poses with valid calibration found!").arg(poses.size()), Qt::darkYellow);
02851                                         _progressDialog->setAutoClose(false);
02852                                         UWARN("No camera poses!?");
02853                                 }
02854                                 else
02855                                 {
02856                                         _progressDialog->appendText(tr("No polygons!?"), Qt::darkYellow);
02857                                         _progressDialog->setAutoClose(false);
02858                                         UWARN("No polygons!");
02859                                 }
02860 
02861                                 _progressDialog->appendText(tr("TextureMesh %1 created [cameras=%2] (%3/%4).").arg(iter->first).arg(cameraPoses.size()).arg(++i).arg(meshes.size()));
02862                                 _progressDialog->incrementStep();
02863                                 QApplication::processEvents();
02864                                 if(_canceled)
02865                                 {
02866                                         return false;
02867                                 }
02868                         }
02869 
02870                         if(textureMeshes.size() > 1 && _ui->checkBox_assemble->isChecked())
02871                         {
02872                                 UDEBUG("Concatenate texture meshes");
02873                                 _progressDialog->appendText(tr("Assembling %1 meshes...").arg(textureMeshes.size()));
02874                                 QApplication::processEvents();
02875                                 uSleep(100);
02876                                 QApplication::processEvents();
02877 
02878                                 pcl::TextureMesh::Ptr assembledMesh = util3d::concatenateTextureMeshes(uValuesList(textureMeshes));
02879                                 textureMeshes.clear();
02880                                 textureMeshes.insert(std::make_pair(0, assembledMesh));
02881                         }
02882 
02883                 }
02884                 UDEBUG("");
02885                 return true;
02886         }
02887         return false;
02888 }
02889 
02890 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > ExportCloudsDialog::getClouds(
02891                 const std::map<int, Transform> & poses,
02892                 const QMap<int, Signature> & cachedSignatures,
02893                 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
02894                 const std::map<int, LaserScan> & cachedScans,
02895                 const ParametersMap & parameters,
02896                 bool & has2dScans) const
02897 {
02898         has2dScans = false;
02899         std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
02900         int index=1;
02901         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr previousCloud;
02902         pcl::IndicesPtr previousIndices;
02903         Transform previousPose;
02904         for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end() && !_canceled; ++iter, ++index)
02905         {
02906                 int points = 0;
02907                 int totalIndices = 0;
02908                 if(!iter->second.isNull())
02909                 {
02910                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
02911                         pcl::IndicesPtr indices(new std::vector<int>);
02912                         Transform localTransform = Transform::getIdentity();
02913                         if(_ui->checkBox_regenerate->isChecked())
02914                         {
02915                                 SensorData data;
02916                                 cv::Mat image, depth;
02917                                 LaserScan scan;
02918                                 if(cachedSignatures.contains(iter->first))
02919                                 {
02920                                         const Signature & s = cachedSignatures.find(iter->first).value();
02921                                         data = s.sensorData();
02922                                         data.uncompressData(
02923                                                         _ui->checkBox_fromDepth->isChecked()?&image:0,
02924                                                         _ui->checkBox_fromDepth->isChecked()?&depth:0,
02925                                                         !_ui->checkBox_fromDepth->isChecked()?&scan:0);
02926                                 }
02927                                 else if(_dbDriver)
02928                                 {
02929                                         _dbDriver->getNodeData(iter->first, data, _ui->checkBox_fromDepth->isChecked(), !_ui->checkBox_fromDepth->isChecked(), false, false);
02930                                         data.uncompressData(
02931                                                         _ui->checkBox_fromDepth->isChecked()?&image:0,
02932                                                         _ui->checkBox_fromDepth->isChecked()?&depth:0,
02933                                                         !_ui->checkBox_fromDepth->isChecked()?&scan:0);
02934                                 }
02935 
02936                                 if(_ui->checkBox_fromDepth->isChecked() && !image.empty() && !depth.empty())
02937                                 {
02938                                         if(_ui->spinBox_fillDepthHoles->value() > 0)
02939                                         {
02940                                                 depth = util2d::fillDepthHoles(depth, _ui->spinBox_fillDepthHoles->value(), float(_ui->spinBox_fillDepthHolesError->value())/100.f);
02941                                         }
02942 
02943                                         if(!_ui->lineEdit_distortionModel->text().isEmpty() &&
02944                                            QFileInfo(_ui->lineEdit_distortionModel->text()).exists())
02945                                         {
02946                                                 clams::DiscreteDepthDistortionModel model;
02947                                                 model.load(_ui->lineEdit_distortionModel->text().toStdString());
02948                                                 depth = depth.clone();// make sure we are not modifying data in cached signatures.
02949                                                 model.undistort(depth);
02950                                                 data.setDepthOrRightRaw(depth);
02951                                         }
02952 
02953                                         // bilateral filtering
02954                                         if(_ui->checkBox_bilateral->isChecked())
02955                                         {
02956                                                 depth = util2d::fastBilateralFiltering(depth,
02957                                                                 _ui->doubleSpinBox_bilateral_sigmaS->value(),
02958                                                                 _ui->doubleSpinBox_bilateral_sigmaR->value());
02959                                                 data.setDepthOrRightRaw(depth);
02960                                         }
02961 
02962                                         UASSERT(iter->first == data.id());
02963                                         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
02964                                         std::vector<float> roiRatios;
02965                                         if(!_ui->lineEdit_roiRatios->text().isEmpty())
02966                                         {
02967                                                 QStringList values = _ui->lineEdit_roiRatios->text().split(' ');
02968                                                 if(values.size() == 4)
02969                                                 {
02970                                                         roiRatios.resize(4);
02971                                                         for(int i=0; i<values.size(); ++i)
02972                                                         {
02973                                                                 roiRatios[i] = uStr2Float(values[i].toStdString().c_str());
02974                                                         }
02975                                                 }
02976                                         }
02977                                         cloudWithoutNormals = util3d::cloudRGBFromSensorData(
02978                                                         data,
02979                                                         _ui->spinBox_decimation->value() == 0?1:_ui->spinBox_decimation->value(),
02980                                                         _ui->doubleSpinBox_maxDepth->value(),
02981                                                         _ui->doubleSpinBox_minDepth->value(),
02982                                                         indices.get(),
02983                                                         parameters,
02984                                                         roiRatios);
02985 
02986                                         if(cloudWithoutNormals->size())
02987                                         {
02988                                                 // Don't voxelize if we create organized mesh
02989                                                 if(!(_ui->comboBox_pipeline->currentIndex()==0 && _ui->checkBox_meshing->isChecked()) && _ui->doubleSpinBox_voxelSize_assembled->value()>0.0)
02990                                                 {
02991                                                         cloudWithoutNormals = util3d::voxelize(cloudWithoutNormals, indices, _ui->doubleSpinBox_voxelSize_assembled->value());
02992                                                         indices->resize(cloudWithoutNormals->size());
02993                                                         for(unsigned int i=0; i<indices->size(); ++i)
02994                                                         {
02995                                                                 indices->at(i) = i;
02996                                                         }
02997                                                 }
02998 
02999                                                 // view point
03000                                                 Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
03001                                                 if(data.cameraModels().size() && !data.cameraModels()[0].localTransform().isNull())
03002                                                 {
03003                                                         localTransform = data.cameraModels()[0].localTransform();
03004                                                         viewPoint[0] = data.cameraModels()[0].localTransform().x();
03005                                                         viewPoint[1] = data.cameraModels()[0].localTransform().y();
03006                                                         viewPoint[2] = data.cameraModels()[0].localTransform().z();
03007                                                 }
03008                                                 else if(!data.stereoCameraModel().localTransform().isNull())
03009                                                 {
03010                                                         localTransform = data.stereoCameraModel().localTransform();
03011                                                         viewPoint[0] = data.stereoCameraModel().localTransform().x();
03012                                                         viewPoint[1] = data.stereoCameraModel().localTransform().y();
03013                                                         viewPoint[2] = data.stereoCameraModel().localTransform().z();
03014                                                 }
03015 
03016                                                 pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
03017                                                 pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
03018 
03019                                                 if(_ui->checkBox_subtraction->isChecked() &&
03020                                                    _ui->doubleSpinBox_subtractPointFilteringRadius->value() > 0.0)
03021                                                 {
03022                                                         pcl::IndicesPtr beforeSubtractionIndices = indices;
03023                                                         if(     cloud->size() &&
03024                                                                 previousCloud.get() != 0 &&
03025                                                                 previousIndices.get() != 0 &&
03026                                                                 previousIndices->size() &&
03027                                                                 !previousPose.isNull())
03028                                                         {
03029                                                                 rtabmap::Transform t = iter->second.inverse() * previousPose;
03030                                                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformedCloud = rtabmap::util3d::transformPointCloud(previousCloud, t);
03031                                                                 indices = rtabmap::util3d::subtractFiltering(
03032                                                                                 cloud,
03033                                                                                 indices,
03034                                                                                 transformedCloud,
03035                                                                                 previousIndices,
03036                                                                                 _ui->doubleSpinBox_subtractPointFilteringRadius->value(),
03037                                                                                 _ui->doubleSpinBox_subtractPointFilteringAngle->value(),
03038                                                                                 _ui->spinBox_subtractFilteringMinPts->value());
03039                                                         }
03040                                                         previousCloud = cloud;
03041                                                         previousIndices = beforeSubtractionIndices;
03042                                                         previousPose = iter->second;
03043                                                 }
03044                                         }
03045                                 }
03046                                 else if(!_ui->checkBox_fromDepth->isChecked() && !scan.isEmpty())
03047                                 {
03048                                         bool is2D = scan.is2d();
03049                                         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
03050                                         localTransform = Transform::getIdentity();
03051                                         Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
03052                                         localTransform = scan.localTransform();
03053                                         viewPoint[0] = localTransform.x();
03054                                         viewPoint[1] = localTransform.y();
03055                                         viewPoint[2] = localTransform.z();
03056 
03057                                         cloudWithoutNormals = util3d::laserScanToPointCloudRGB(scan, localTransform); // put in base frame by default
03058                                         if(cloudWithoutNormals->size())
03059                                         {
03060                                                 if(_ui->doubleSpinBox_voxelSize_assembled->value()>0.0)
03061                                                 {
03062                                                         cloudWithoutNormals = util3d::voxelize(cloudWithoutNormals, _ui->doubleSpinBox_voxelSize_assembled->value());
03063                                                 }
03064                                                 indices->resize(cloudWithoutNormals->size());
03065                                                 for(unsigned int i=0; i<indices->size(); ++i)
03066                                                 {
03067                                                         indices->at(i) = i;
03068                                                 }
03069                                                 pcl::PointCloud<pcl::Normal>::Ptr normals;
03070                                                 if(is2D)
03071                                                 {
03072                                                         // set nan normals
03073                                                         normals.reset(new pcl::PointCloud<pcl::Normal>);
03074                                                         normals->resize(cloudWithoutNormals->size());
03075                                                         for(unsigned int i=0;i<cloudWithoutNormals->size(); ++i)
03076                                                         {
03077                                                                 normals->points[i].normal_x =std::numeric_limits<float>::quiet_NaN();
03078                                                                 normals->points[i].normal_y =std::numeric_limits<float>::quiet_NaN();
03079                                                                 normals->points[i].normal_z =std::numeric_limits<float>::quiet_NaN();
03080                                                         }
03081                                                         has2dScans = true;
03082                                                 }
03083                                                 else
03084                                                 {
03085                                                         normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
03086                                                 }
03087                                                 pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
03088                                         }
03089                                 }
03090                                 else
03091                                 {
03092                                         int weight = 0;
03093                                         if(cachedSignatures.contains(iter->first))
03094                                         {
03095                                                 const Signature & s = cachedSignatures.find(iter->first).value();
03096                                                 weight = s.getWeight();
03097                                         }
03098                                         else if(_dbDriver)
03099                                         {
03100                                                 _dbDriver->getWeight(iter->first, weight);
03101                                         }
03102                                         if(weight>=0) // don't show error for intermediate nodes
03103                                         {
03104                                                 UERROR("Cloud %d not found in cache!", iter->first);
03105                                         }
03106                                 }
03107                         }
03108                         else if(_ui->checkBox_fromDepth->isChecked() && uContains(cachedClouds, iter->first))
03109                         {
03110                                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
03111                                 if(!_ui->checkBox_meshing->isChecked() &&
03112                                    _ui->doubleSpinBox_voxelSize_assembled->value() > 0.0)
03113                                 {
03114                                         cloudWithoutNormals = util3d::voxelize(
03115                                                         cachedClouds.at(iter->first).first,
03116                                                         cachedClouds.at(iter->first).second,
03117                                                         _ui->doubleSpinBox_voxelSize_assembled->value());
03118 
03119                                         //generate indices for all points (they are all valid)
03120                                         indices->resize(cloudWithoutNormals->size());
03121                                         for(unsigned int i=0; i<cloudWithoutNormals->size(); ++i)
03122                                         {
03123                                                 indices->at(i) = i;
03124                                         }
03125                                 }
03126                                 else
03127                                 {
03128                                         cloudWithoutNormals = cachedClouds.at(iter->first).first;
03129                                         indices = cachedClouds.at(iter->first).second;
03130                                 }
03131 
03132                                 // view point
03133                                 Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
03134                                 std::vector<CameraModel> models;
03135                                 StereoCameraModel stereoModel;
03136                                 if(cachedSignatures.contains(iter->first))
03137                                 {
03138                                         const Signature & s = cachedSignatures.find(iter->first).value();
03139                                         models = s.sensorData().cameraModels();
03140                                         stereoModel = s.sensorData().stereoCameraModel();
03141                                 }
03142                                 else if(_dbDriver)
03143                                 {
03144                                         _dbDriver->getCalibration(iter->first, models, stereoModel);
03145                                 }
03146 
03147                                 if(models.size() && !models[0].localTransform().isNull())
03148                                 {
03149                                         localTransform = models[0].localTransform();
03150                                         viewPoint[0] = models[0].localTransform().x();
03151                                         viewPoint[1] = models[0].localTransform().y();
03152                                         viewPoint[2] = models[0].localTransform().z();
03153                                 }
03154                                 else if(!stereoModel.localTransform().isNull())
03155                                 {
03156                                         localTransform = stereoModel.localTransform();
03157                                         viewPoint[0] = stereoModel.localTransform().x();
03158                                         viewPoint[1] = stereoModel.localTransform().y();
03159                                         viewPoint[2] = stereoModel.localTransform().z();
03160                                 }
03161                                 else
03162                                 {
03163                                         _progressDialog->appendText(tr("Cached cloud %1 is not found in cached data, the view point for normal computation will not be set (%2/%3).").arg(iter->first).arg(index).arg(poses.size()), Qt::darkYellow);
03164                                 }
03165 
03166                                 pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
03167                                 pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
03168                         }
03169                         else if(!_ui->checkBox_fromDepth->isChecked() && uContains(cachedScans, iter->first))
03170                         {
03171                                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
03172 
03173                                 localTransform = cachedScans.at(iter->first).localTransform();
03174                                 Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
03175                                 viewPoint[0] = localTransform.x();
03176                                 viewPoint[1] = localTransform.y();
03177                                 viewPoint[2] = localTransform.z();
03178 
03179                                 bool is2D = cachedScans.at(iter->first).is2d();
03180                                 cloudWithoutNormals = util3d::laserScanToPointCloudRGB(cachedScans.at(iter->first), cachedScans.at(iter->first).localTransform());
03181                                 if(cloudWithoutNormals->size())
03182                                 {
03183                                         if(_ui->doubleSpinBox_voxelSize_assembled->value()>0.0)
03184                                         {
03185                                                 cloudWithoutNormals = util3d::voxelize(cloudWithoutNormals, _ui->doubleSpinBox_voxelSize_assembled->value());
03186                                         }
03187                                         indices->resize(cloudWithoutNormals->size());
03188                                         for(unsigned int i=0; i<indices->size(); ++i)
03189                                         {
03190                                                 indices->at(i) = i;
03191                                         }
03192 
03193                                         pcl::PointCloud<pcl::Normal>::Ptr normals;
03194                                         if(is2D)
03195                                         {
03196                                                 // set nan normals
03197                                                 normals.reset(new pcl::PointCloud<pcl::Normal>);
03198                                                 normals->resize(cloudWithoutNormals->size());
03199                                                 for(unsigned int i=0;i<cloudWithoutNormals->size(); ++i)
03200                                                 {
03201                                                         normals->points[i].normal_x =std::numeric_limits<float>::quiet_NaN();
03202                                                         normals->points[i].normal_y =std::numeric_limits<float>::quiet_NaN();
03203                                                         normals->points[i].normal_z =std::numeric_limits<float>::quiet_NaN();
03204                                                 }
03205                                                 has2dScans = true;
03206                                         }
03207                                         else
03208                                         {
03209                                                 normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
03210                                         }
03211                                         pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
03212                                 }
03213                         }
03214                         else
03215                         {
03216                                 int weight = 0;
03217                                 if(cachedSignatures.contains(iter->first))
03218                                 {
03219                                         const Signature & s = cachedSignatures.find(iter->first).value();
03220                                         weight = s.getWeight();
03221                                 }
03222                                 else if(_dbDriver)
03223                                 {
03224                                         _dbDriver->getWeight(iter->first, weight);
03225                                 }
03226                                 if(weight>=0) // don't show error for intermediate nodes
03227                                 {
03228                                         _progressDialog->appendText(tr("Cached cloud %1 not found. You may want to regenerate the clouds (%2/%3).").arg(iter->first).arg(index).arg(poses.size()), Qt::darkYellow);
03229                                 }
03230                         }
03231 
03232                         if(indices->size())
03233                         {
03234                                 if(_ui->checkBox_filtering->isChecked() &&
03235                                         _ui->doubleSpinBox_filteringRadius->value() > 0.0f &&
03236                                         _ui->spinBox_filteringMinNeighbors->value() > 0)
03237                                 {
03238                                         indices = util3d::radiusFiltering(cloud, indices, _ui->doubleSpinBox_filteringRadius->value(), _ui->spinBox_filteringMinNeighbors->value());
03239                                 }
03240 
03241                                 if((_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex()==2) && cloud->isOrganized())
03242                                 {
03243                                         cloud = util3d::transformPointCloud(cloud, localTransform.inverse()); // put back in camera frame
03244                                 }
03245                                 else if(_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex()==3)
03246                                 {
03247                                         cloud = util3d::transformPointCloud(cloud, localTransform.inverse()); // put back in scan frame
03248                                 }
03249 
03250                                 clouds.insert(std::make_pair(iter->first, std::make_pair(cloud, indices)));
03251                                 points = (int)cloud->size();
03252                                 totalIndices = (int)indices->size();
03253                         }
03254                 }
03255                 else
03256                 {
03257                         UERROR("transform is null!?");
03258                 }
03259 
03260                 if(points>0)
03261                 {
03262                         if(_ui->checkBox_regenerate->isChecked())
03263                         {
03264                                 _progressDialog->appendText(tr("Generated cloud %1 with %2 points and %3 indices (%4/%5).")
03265                                                 .arg(iter->first).arg(points).arg(totalIndices).arg(index).arg(poses.size()));
03266                         }
03267                         else
03268                         {
03269                                 _progressDialog->appendText(tr("Copied cloud %1 from cache with %2 points and %3 indices (%4/%5).")
03270                                                 .arg(iter->first).arg(points).arg(totalIndices).arg(index).arg(poses.size()));
03271                         }
03272                 }
03273                 else
03274                 {
03275                         _progressDialog->appendText(tr("Ignored cloud %1 (%2/%3).").arg(iter->first).arg(index).arg(poses.size()));
03276                 }
03277                 _progressDialog->incrementStep();
03278                 QApplication::processEvents();
03279         }
03280 
03281         return clouds;
03282 }
03283 
03284 
03285 void ExportCloudsDialog::saveClouds(
03286                 const QString & workingDirectory,
03287                 const std::map<int, Transform> & poses,
03288                 const std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds,
03289                 bool binaryMode)
03290 {
03291         if(clouds.size() == 1)
03292         {
03293                 QString path = QFileDialog::getSaveFileName(this, tr("Save cloud to ..."), workingDirectory+QDir::separator()+"cloud.ply", tr("Point cloud data (*.ply *.pcd)"));
03294                 if(!path.isEmpty())
03295                 {
03296                         if(clouds.begin()->second->size())
03297                         {
03298                                 _progressDialog->appendText(tr("Saving the cloud (%1 points)...").arg(clouds.begin()->second->size()));
03299 
03300                                 bool success =false;
03301                                 if(QFileInfo(path).suffix() == "pcd")
03302                                 {
03303                                         success = pcl::io::savePCDFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
03304                                 }
03305                                 else if(QFileInfo(path).suffix() == "ply")
03306                                 {
03307                                         success = pcl::io::savePLYFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
03308                                 }
03309                                 else if(QFileInfo(path).suffix() == "")
03310                                 {
03311                                         //use ply by default
03312                                         path += ".ply";
03313                                         success = pcl::io::savePLYFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
03314                                 }
03315                                 else
03316                                 {
03317                                         UERROR("Extension not recognized! (%s) Should be one of (*.ply *.pcd).", QFileInfo(path).suffix().toStdString().c_str());
03318                                 }
03319                                 if(success)
03320                                 {
03321                                         _progressDialog->incrementStep();
03322                                         _progressDialog->appendText(tr("Saving the cloud (%1 points)... done.").arg(clouds.begin()->second->size()));
03323 
03324                                         QMessageBox::information(this, tr("Save successful!"), tr("Cloud saved to \"%1\"").arg(path));
03325                                 }
03326                                 else
03327                                 {
03328                                         QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
03329                                 }
03330                         }
03331                         else
03332                         {
03333                                 QMessageBox::warning(this, tr("Save failed!"), tr("Cloud is empty..."));
03334                         }
03335                 }
03336         }
03337         else if(clouds.size())
03338         {
03339                 QString path = QFileDialog::getExistingDirectory(this, tr("Save clouds to (*.ply *.pcd)..."), workingDirectory, 0);
03340                 if(!path.isEmpty())
03341                 {
03342                         bool ok = false;
03343                         QStringList items;
03344                         items.push_back("ply");
03345                         items.push_back("pcd");
03346                         QString suffix = QInputDialog::getItem(this, tr("File format"), tr("Which format?"), items, 0, false, &ok);
03347 
03348                         if(ok)
03349                         {
03350                                 QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "cloud", &ok);
03351 
03352                                 if(ok)
03353                                 {
03354                                         for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::const_iterator iter=clouds.begin(); iter!=clouds.end(); ++iter)
03355                                         {
03356                                                 if(iter->second->size())
03357                                                 {
03358                                                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformedCloud;
03359                                                         transformedCloud = util3d::transformPointCloud(iter->second, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
03360 
03361                                                         QString pathFile = path+QDir::separator()+QString("%1%2.%3").arg(prefix).arg(iter->first).arg(suffix);
03362                                                         bool success =false;
03363                                                         if(suffix == "pcd")
03364                                                         {
03365                                                                 success = pcl::io::savePCDFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
03366                                                         }
03367                                                         else if(suffix == "ply")
03368                                                         {
03369                                                                 success = pcl::io::savePLYFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
03370                                                         }
03371                                                         else
03372                                                         {
03373                                                                 UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
03374                                                         }
03375                                                         if(success)
03376                                                         {
03377                                                                 _progressDialog->appendText(tr("Saved cloud %1 (%2 points) to %3.").arg(iter->first).arg(iter->second->size()).arg(pathFile));
03378                                                         }
03379                                                         else
03380                                                         {
03381                                                                 _progressDialog->appendText(tr("Failed saving cloud %1 (%2 points) to %3.").arg(iter->first).arg(iter->second->size()).arg(pathFile), Qt::darkRed);
03382                                                                 _progressDialog->setAutoClose(false);
03383                                                         }
03384                                                 }
03385                                                 else
03386                                                 {
03387                                                         _progressDialog->appendText(tr("Cloud %1 is empty!").arg(iter->first));
03388                                                 }
03389                                                 _progressDialog->incrementStep();
03390                                                 QApplication::processEvents();
03391                                                 if(_canceled)
03392                                                 {
03393                                                         return;
03394                                                 }
03395                                         }
03396                                 }
03397                         }
03398                 }
03399         }
03400 }
03401 
03402 void ExportCloudsDialog::saveMeshes(
03403                 const QString & workingDirectory,
03404                 const std::map<int, Transform> & poses,
03405                 const std::map<int, pcl::PolygonMesh::Ptr> & meshes,
03406                 bool binaryMode)
03407 {
03408         if(meshes.size() == 1)
03409         {
03410                 QString path = QFileDialog::getSaveFileName(this, tr("Save mesh to ..."), workingDirectory+QDir::separator()+"mesh.ply", tr("Mesh (*.ply)"));
03411                 if(!path.isEmpty())
03412                 {
03413                         if(meshes.begin()->second->polygons.size())
03414                         {
03415                                 _progressDialog->appendText(tr("Saving the mesh (%1 polygons)...").arg(meshes.begin()->second->polygons.size()));
03416                                 QApplication::processEvents();
03417                                 uSleep(100);
03418                                 QApplication::processEvents();
03419 
03420                                 bool success =false;
03421                                 if(QFileInfo(path).suffix() == "")
03422                                 {
03423                                         path += ".ply";
03424                                 }
03425 
03426                                 if(QFileInfo(path).suffix() == "ply")
03427                                 {
03428                                         if(binaryMode)
03429                                         {
03430                                                 success = pcl::io::savePLYFileBinary(path.toStdString(), *meshes.begin()->second) == 0;
03431                                         }
03432                                         else
03433                                         {
03434                                                 success = pcl::io::savePLYFile(path.toStdString(), *meshes.begin()->second) == 0;
03435                                         }
03436                                 }
03437                                 else if(QFileInfo(path).suffix() == "obj")
03438                                 {
03439                                         success = pcl::io::saveOBJFile(path.toStdString(), *meshes.begin()->second) == 0;
03440                                 }
03441                                 else
03442                                 {
03443                                         UERROR("Extension not recognized! (%s) Should be (*.ply).", QFileInfo(path).suffix().toStdString().c_str());
03444                                 }
03445                                 if(success)
03446                                 {
03447                                         _progressDialog->incrementStep();
03448                                         _progressDialog->appendText(tr("Saving the mesh (%1 polygons)... done.").arg(meshes.begin()->second->polygons.size()));
03449 
03450                                         QMessageBox::information(this, tr("Save successful!"), tr("Mesh saved to \"%1\"").arg(path));
03451                                 }
03452                                 else
03453                                 {
03454                                         QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
03455                                 }
03456                         }
03457                         else
03458                         {
03459                                 QMessageBox::warning(this, tr("Save failed!"), tr("Cloud is empty..."));
03460                         }
03461                 }
03462         }
03463         else if(meshes.size())
03464         {
03465                 QString path = QFileDialog::getExistingDirectory(this, tr("Save meshes to (*.ply *.obj)..."), workingDirectory, 0);
03466                 if(!path.isEmpty())
03467                 {
03468                         bool ok = false;
03469                         QStringList items;
03470                         items.push_back("ply");
03471                         items.push_back("obj");
03472                         QString suffix = QInputDialog::getItem(this, tr("File format"), tr("Which format?"), items, 0, false, &ok);
03473 
03474                         if(ok)
03475                         {
03476                                 QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "mesh", &ok);
03477 
03478                                 if(ok)
03479                                 {
03480                                         for(std::map<int, pcl::PolygonMesh::Ptr>::const_iterator iter=meshes.begin(); iter!=meshes.end(); ++iter)
03481                                         {
03482                                                 if(iter->second->polygons.size())
03483                                                 {
03484                                                         pcl::PolygonMesh mesh;
03485                                                         mesh.polygons = iter->second->polygons;
03486                                                         bool isRGB = false;
03487                                                         for(unsigned int i=0; i<iter->second->cloud.fields.size(); ++i)
03488                                                         {
03489                                                                 if(iter->second->cloud.fields[i].name.compare("rgb") == 0)
03490                                                                 {
03491                                                                         isRGB=true;
03492                                                                         break;
03493                                                                 }
03494                                                         }
03495                                                         if(isRGB)
03496                                                         {
03497                                                                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZRGB>);
03498                                                                 pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
03499                                                                 tmp = util3d::transformPointCloud(tmp, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
03500                                                                 pcl::toPCLPointCloud2(*tmp, mesh.cloud);
03501                                                         }
03502                                                         else
03503                                                         {
03504                                                                 pcl::PointCloud<pcl::PointXYZ>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZ>);
03505                                                                 pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
03506                                                                 tmp = util3d::transformPointCloud(tmp, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
03507                                                                 pcl::toPCLPointCloud2(*tmp, mesh.cloud);
03508                                                         }
03509 
03510                                                         QString pathFile = path+QDir::separator()+QString("%1%2.%3").arg(prefix).arg(iter->first).arg(suffix);
03511                                                         bool success =false;
03512                                                         if(suffix == "ply")
03513                                                         {
03514                                                                 if(binaryMode)
03515                                                                 {
03516                                                                         success = pcl::io::savePLYFileBinary(pathFile.toStdString(), mesh) == 0;
03517                                                                 }
03518                                                                 else
03519                                                                 {
03520                                                                         success = pcl::io::savePLYFile(pathFile.toStdString(), mesh) == 0;
03521                                                                 }
03522                                                         }
03523                                                         else if(suffix == "obj")
03524                                                         {
03525                                                                 success = pcl::io::saveOBJFile(pathFile.toStdString(), mesh) == 0;
03526                                                         }
03527                                                         else
03528                                                         {
03529                                                                 UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
03530                                                         }
03531                                                         if(success)
03532                                                         {
03533                                                                 _progressDialog->appendText(tr("Saved mesh %1 (%2 polygons) to %3.")
03534                                                                                 .arg(iter->first).arg(iter->second->polygons.size()).arg(pathFile));
03535                                                         }
03536                                                         else
03537                                                         {
03538                                                                 _progressDialog->appendText(tr("Failed saving mesh %1 (%2 polygons) to %3.")
03539                                                                                 .arg(iter->first).arg(iter->second->polygons.size()).arg(pathFile), Qt::darkRed);
03540                                                                 _progressDialog->setAutoClose(false);
03541                                                         }
03542                                                 }
03543                                                 else
03544                                                 {
03545                                                         _progressDialog->appendText(tr("Mesh %1 is empty!").arg(iter->first));
03546                                                 }
03547                                                 _progressDialog->incrementStep();
03548                                                 QApplication::processEvents();
03549                                                 if(_canceled)
03550                                                 {
03551                                                         return;
03552                                                 }
03553                                         }
03554                                 }
03555                         }
03556                 }
03557         }
03558 }
03559 
03560 void ExportCloudsDialog::saveTextureMeshes(
03561                 const QString & workingDirectory,
03562                 const std::map<int, Transform> & poses,
03563                 std::map<int, pcl::TextureMesh::Ptr> & meshes,
03564                 const QMap<int, Signature> & cachedSignatures,
03565                 const std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels)
03566 {
03567         std::map<int, cv::Mat> images;
03568         std::map<int, std::vector<CameraModel> > calibrations;
03569         for(QMap<int, Signature>::const_iterator iter=cachedSignatures.constBegin(); iter!=cachedSignatures.constEnd(); ++iter)
03570         {
03571                 std::vector<CameraModel> models;
03572                 if(iter->sensorData().cameraModels().size())
03573                 {
03574                         models = iter->sensorData().cameraModels();
03575                 }
03576                 else if(iter->sensorData().stereoCameraModel().isValidForProjection())
03577                 {
03578                         models.push_back(iter->sensorData().stereoCameraModel().left());
03579                 }
03580 
03581                 if(!models.empty())
03582                 {
03583                         if(!iter->sensorData().imageRaw().empty())
03584                         {
03585                                 calibrations.insert(std::make_pair(iter.key(), models));
03586                                 images.insert(std::make_pair(iter.key(), iter->sensorData().imageRaw()));
03587                         }
03588                         else if(!iter->sensorData().imageCompressed().empty())
03589                         {
03590                                 calibrations.insert(std::make_pair(iter.key(), models));
03591                                 images.insert(std::make_pair(iter.key(), iter->sensorData().imageCompressed()));
03592                         }
03593                 }
03594         }
03595         int textureSize = 1024;
03596         if(_ui->comboBox_meshingTextureSize->currentIndex() > 0)
03597         {
03598                 textureSize = 128 << _ui->comboBox_meshingTextureSize->currentIndex(); // start at 256
03599         }
03600         int blendingDecimation = 0;
03601         if(_ui->checkBox_blending->isChecked())
03602         {
03603                 if(_ui->comboBox_blendingDecimation->currentIndex() > 0)
03604                 {
03605                         blendingDecimation = 1 << (_ui->comboBox_blendingDecimation->currentIndex()-1);
03606                 }
03607         }
03608 
03609         if(meshes.size() == 1)
03610         {
03611                 QString path = QFileDialog::getSaveFileName(this, tr("Save texture mesh to ..."), workingDirectory+QDir::separator()+"mesh.obj", tr("Mesh (*.obj)"));
03612                 if(!path.isEmpty())
03613                 {
03614                         if(meshes.begin()->second->tex_materials.size())
03615                         {
03616                                 _progressDialog->appendText(tr("Saving the mesh (with %1 textures)...").arg(meshes.begin()->second->tex_materials.size()));
03617                                 QApplication::processEvents();
03618                                 uSleep(100);
03619                                 QApplication::processEvents();
03620 
03621                                 bool success =false;
03622                                 if(QFileInfo(path).suffix() == "")
03623                                 {
03624                                         path += ".obj";
03625                                 }
03626 
03627                                 pcl::TextureMesh::Ptr mesh = meshes.begin()->second;
03628 
03629                                 cv::Mat globalTextures;
03630                                 bool texturesMerged = _ui->comboBox_meshingTextureSize->isEnabled() && _ui->comboBox_meshingTextureSize->currentIndex() > 0;
03631                                 if(texturesMerged && mesh->tex_materials.size()>1)
03632                                 {
03633                                         globalTextures = util3d::mergeTextures(
03634                                                         *mesh,
03635                                                         images,
03636                                                         calibrations,
03637                                                         0,
03638                                                         _dbDriver,
03639                                                         textureSize,
03640                                                         _ui->spinBox_mesh_maxTextures->value(),
03641                                                         textureVertexToPixels,
03642                                                         _ui->checkBox_gainCompensation->isChecked(),
03643                                                         _ui->doubleSpinBox_gainBeta->value(),
03644                                                         _ui->checkBox_gainRGB->isChecked(),
03645                                                         _ui->checkBox_blending->isChecked(),
03646                                                         blendingDecimation,
03647                                                         _ui->spinBox_textureBrightnessContrastRatioLow->value(),
03648                                                         _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
03649                                                         _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked());
03650                                 }
03651 
03652                                 bool singleTexture = mesh->tex_materials.size() == 1;
03653                                 if(!singleTexture)
03654                                 {
03655                                         removeDirRecursively(QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName());
03656                                         QDir(QFileInfo(path).absoluteDir().absolutePath()).mkdir(QFileInfo(path).baseName());
03657                                 }
03658 
03659                                 // used for multi camera texturing, to avoid reloading same texture for sub cameras
03660                                 cv::Mat previousImage;
03661                                 int previousTextureId = 0;
03662                                 std::vector<CameraModel> previousCameraModels;
03663 
03664                                 cv::Size imageSize;
03665                                 for(unsigned int i=0; i<mesh->tex_materials.size(); ++i)
03666                                 {
03667                                         if(!mesh->tex_materials[i].tex_file.empty())
03668                                         {
03669                                                 // absolute path
03670                                                 QString fullPath;
03671                                                 if(singleTexture)
03672                                                 {
03673                                                         fullPath = QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName()+_ui->comboBox_meshingTextureFormat->currentText();
03674                                                 }
03675                                                 else
03676                                                 {
03677                                                         fullPath = QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName()+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText();
03678                                                 }
03679                                                 UDEBUG("Saving %s...", fullPath.toStdString().c_str());
03680                                                 if(singleTexture || !QFileInfo(fullPath).exists())
03681                                                 {
03682                                                         std::list<std::string> texFileSplit = uSplit(mesh->tex_materials[i].tex_file, '_');
03683                                                         if(texFileSplit.size() && uIsInteger(texFileSplit.front(), false))
03684                                                         {
03685                                                                 int textureId = uStr2Int(texFileSplit.front());
03686                                                                 int textureSubCamera = -1;
03687                                                                 if(texFileSplit.size() == 2 &&
03688                                                                    uIsInteger(texFileSplit.back(), false))
03689                                                                 {
03690                                                                         textureSubCamera = uStr2Int(texFileSplit.back());
03691                                                                 }
03692                                                                 cv::Mat image;
03693                                                                 std::vector<CameraModel> cameraModels;
03694 
03695                                                                 if(textureId == previousTextureId)
03696                                                                 {
03697                                                                         image = previousImage;
03698                                                                         cameraModels = previousCameraModels;
03699                                                                 }
03700                                                                 else
03701                                                                 {
03702                                                                         if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
03703                                                                         {
03704                                                                                 cachedSignatures.value(textureId).sensorData().uncompressDataConst(&image, 0);
03705                                                                                 cameraModels = cachedSignatures.value(textureId).sensorData().cameraModels();
03706                                                                         }
03707                                                                         else if(_dbDriver)
03708                                                                         {
03709                                                                                 SensorData data;
03710                                                                                 _dbDriver->getNodeData(textureId, data, true, false, false, false);
03711                                                                                 data.uncompressDataConst(&image, 0);
03712                                                                                 StereoCameraModel stereoModel;
03713                                                                                 _dbDriver->getCalibration(textureId, cameraModels, stereoModel);
03714                                                                         }
03715 
03716                                                                         previousImage = image;
03717                                                                         previousCameraModels = cameraModels;
03718                                                                         previousTextureId = textureId;
03719                                                                 }
03720                                                                 UASSERT(!image.empty());
03721                                                                 imageSize = image.size();
03722                                                                 if(textureSubCamera>=0)
03723                                                                 {
03724                                                                         UASSERT(cameraModels.size());
03725                                                                         imageSize.width/=cameraModels.size();
03726                                                                         image = image.colRange(imageSize.width*textureSubCamera, imageSize.width*(textureSubCamera+1));
03727                                                                 }
03728                                                                 if(_ui->checkBox_gainCompensation->isChecked() && _compensator && _compensator->getIndex(textureId) >= 0)
03729                                                                 {
03730                                                                         _compensator->apply(textureId, image, _ui->checkBox_gainRGB->isChecked());
03731                                                                 }
03732 
03733                                                                 if(!cv::imwrite(fullPath.toStdString(), image))
03734                                                                 {
03735                                                                         _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
03736                                                                                         .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
03737                                                                         _progressDialog->setAutoClose(false);
03738                                                                 }
03739                                                         }
03740                                                         else if(imageSize.height && imageSize.width)
03741                                                         {
03742                                                                 // make a blank texture
03743                                                                 cv::Mat image = cv::Mat::ones(imageSize, CV_8UC1)*255;
03744                                                                 cv::imwrite(fullPath.toStdString(), image);
03745                                                         }
03746                                                         else if(!globalTextures.empty())
03747                                                         {
03748                                                                 if(!cv::imwrite(fullPath.toStdString(), globalTextures(cv::Range::all(), cv::Range(i*globalTextures.rows, (i+1)*globalTextures.rows))))
03749                                                                 {
03750                                                                         _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
03751                                                                                         .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
03752                                                                         _progressDialog->setAutoClose(false);
03753                                                                 }
03754                                                         }
03755                                                         else
03756                                                         {
03757                                                                 UWARN("Ignored texture %s (no image size set yet)", mesh->tex_materials[i].tex_file.c_str());
03758                                                         }
03759                                                 }
03760                                                 else
03761                                                 {
03762                                                         UWARN("File %s already exists!", fullPath.toStdString().c_str());
03763                                                 }
03764                                                 // relative path
03765                                                 if(singleTexture)
03766                                                 {
03767                                                         mesh->tex_materials[i].tex_file=QFileInfo(path).baseName().toStdString()+_ui->comboBox_meshingTextureFormat->currentText().toStdString();
03768                                                 }
03769                                                 else
03770                                                 {
03771                                                         mesh->tex_materials[i].tex_file=(QFileInfo(path).baseName()+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
03772                                                 }
03773                                         }
03774                                 }
03775 
03776                                 success = pcl::io::saveOBJFile(path.toStdString(), *mesh) == 0;
03777                                 if(success)
03778                                 {
03779                                         _progressDialog->incrementStep();
03780                                         _progressDialog->appendText(tr("Saving the mesh (with %1 textures)... done.").arg(mesh->tex_materials.size()));
03781 
03782                                         QMessageBox::information(this, tr("Save successful!"), tr("Mesh saved to \"%1\"").arg(path));
03783                                 }
03784                                 else
03785                                 {
03786                                         QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
03787                                 }
03788                         }
03789                         else
03790                         {
03791                                 QMessageBox::warning(this, tr("Save failed!"), tr("No textures..."));
03792                         }
03793                 }
03794         }
03795         else if(meshes.size())
03796         {
03797                 QString path = QFileDialog::getExistingDirectory(this, tr("Save texture meshes to (*.obj)..."), workingDirectory, 0);
03798                 if(!path.isEmpty())
03799                 {
03800                         bool ok = false;
03801                         QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "mesh", &ok);
03802                         QString suffix = "obj";
03803 
03804                         if(ok)
03805                         {
03806                                 for(std::map<int, pcl::TextureMesh::Ptr>::iterator iter=meshes.begin(); iter!=meshes.end(); ++iter)
03807                                 {
03808                                         QString currentPrefix=prefix+QString::number(iter->first);
03809                                         if(iter->second->tex_materials.size())
03810                                         {
03811                                                 pcl::TextureMesh::Ptr mesh = iter->second;
03812                                                 cv::Mat globalTextures;
03813                                                 bool texturesMerged = _ui->comboBox_meshingTextureSize->isEnabled() && _ui->comboBox_meshingTextureSize->currentIndex() > 0;
03814                                                 if(texturesMerged && mesh->tex_materials.size()>1)
03815                                                 {
03816                                                         globalTextures = util3d::mergeTextures(
03817                                                                         *mesh,
03818                                                                         images,
03819                                                                         calibrations,
03820                                                                         0,
03821                                                                         _dbDriver,
03822                                                                         textureSize,
03823                                                                         _ui->spinBox_mesh_maxTextures->value(),
03824                                                                         textureVertexToPixels,
03825                                                                         _ui->checkBox_gainCompensation->isChecked(),
03826                                                                         _ui->doubleSpinBox_gainBeta->value(),
03827                                                                         _ui->checkBox_gainRGB->isChecked(),
03828                                                                         _ui->checkBox_blending->isChecked(),
03829                                                                         blendingDecimation,
03830                                                                         _ui->spinBox_textureBrightnessContrastRatioLow->value(),
03831                                                                         _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
03832                                                                         _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked());
03833                                                 }
03834                                                 bool singleTexture = mesh->tex_materials.size() == 1;
03835                                                 if(!singleTexture)
03836                                                 {
03837                                                         removeDirRecursively(path+QDir::separator()+currentPrefix);
03838                                                         QDir(path).mkdir(currentPrefix);
03839                                                 }
03840 
03841                                                 // used for multi camera texturing, to avoid reloading same texture for sub cameras
03842                                                 cv::Mat previousImage;
03843                                                 int previousTextureId = 0;
03844                                                 std::vector<CameraModel> previousCameraModels;
03845 
03846                                                 cv::Size imageSize;
03847                                                 for(unsigned int i=0;i<mesh->tex_materials.size(); ++i)
03848                                                 {
03849                                                         if(!mesh->tex_materials[i].tex_file.empty())
03850                                                         {
03851                                                                 std::list<std::string> texFileSplit = uSplit(mesh->tex_materials[i].tex_file, '_');
03852                                                                 int textureId = 0;
03853                                                                 int textureSubCamera = -1;
03854                                                                 if(texFileSplit.size() && uIsInteger(texFileSplit.front(), false))
03855                                                                 {
03856                                                                         textureId = uStr2Int(texFileSplit.front());
03857                                                                         if(texFileSplit.size() == 2 &&
03858                                                                            uIsInteger(texFileSplit.back(), false))
03859                                                                         {
03860                                                                                 textureSubCamera = uStr2Int(texFileSplit.back());
03861                                                                         }
03862                                                                 }
03863 
03864                                                                 // absolute path
03865                                                                 QString fullPath;
03866                                                                 if(singleTexture)
03867                                                                 {
03868                                                                         mesh->tex_materials[i].tex_file = uNumber2Str(iter->first);
03869                                                                         fullPath = path+QDir::separator()+prefix + QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText();
03870                                                                 }
03871                                                                 else
03872                                                                 {
03873                                                                         fullPath = path+QDir::separator()+currentPrefix+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText();
03874                                                                 }
03875                                                                 if(textureId>0)
03876                                                                 {
03877                                                                         cv::Mat image;
03878                                                                         std::vector<CameraModel> cameraModels;
03879 
03880                                                                         if(textureId == previousTextureId)
03881                                                                         {
03882                                                                                 image = previousImage;
03883                                                                                 cameraModels = previousCameraModels;
03884                                                                         }
03885                                                                         else
03886                                                                         {
03887                                                                                 if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
03888                                                                                 {
03889                                                                                         cachedSignatures.value(textureId).sensorData().uncompressDataConst(&image, 0);
03890                                                                                         cameraModels = cachedSignatures.value(textureId).sensorData().cameraModels();
03891                                                                                 }
03892                                                                                 else if(_dbDriver)
03893                                                                                 {
03894                                                                                         SensorData data;
03895                                                                                         _dbDriver->getNodeData(textureId, data, true, false, false, false);
03896                                                                                         data.uncompressDataConst(&image, 0);
03897                                                                                         StereoCameraModel stereoModel;
03898                                                                                         _dbDriver->getCalibration(textureId, cameraModels, stereoModel);
03899                                                                                 }
03900 
03901                                                                                 previousImage = image;
03902                                                                                 previousCameraModels = cameraModels;
03903                                                                                 previousTextureId = textureId;
03904                                                                         }
03905 
03906 
03907                                                                         UASSERT(!image.empty());
03908                                                                         imageSize = image.size();
03909                                                                         if(textureSubCamera>=0)
03910                                                                         {
03911                                                                                 UASSERT(cameraModels.size());
03912                                                                                 imageSize.width/=cameraModels.size();
03913                                                                                 image = image.colRange(imageSize.width*textureSubCamera, imageSize.width*(textureSubCamera+1));
03914                                                                         }
03915                                                                         if(_ui->checkBox_gainCompensation->isChecked() && _compensator && _compensator->getIndex(textureId) >= 0)
03916                                                                         {
03917                                                                                 _compensator->apply(textureId, image, _ui->checkBox_gainRGB->isChecked());
03918                                                                         }
03919 
03920                                                                         if(!cv::imwrite(fullPath.toStdString(), image))
03921                                                                         {
03922                                                                                 _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
03923                                                                                                 .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
03924                                                                                 _progressDialog->setAutoClose(false);
03925                                                                         }
03926                                                                 }
03927                                                                 else if(imageSize.height && imageSize.width)
03928                                                                 {
03929                                                                         // make a blank texture
03930                                                                         cv::Mat image = cv::Mat::ones(imageSize, CV_8UC1)*255;
03931                                                                         cv::imwrite(fullPath.toStdString(), image);
03932                                                                 }
03933                                                                 else if(!globalTextures.empty())
03934                                                                 {
03935                                                                         if(!cv::imwrite(fullPath.toStdString(), globalTextures(cv::Range::all(), cv::Range(i*globalTextures.rows, (i+1)*globalTextures.rows))))
03936                                                                         {
03937                                                                                 _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
03938                                                                                                 .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
03939                                                                                 _progressDialog->setAutoClose(false);
03940                                                                         }
03941                                                                 }
03942                                                                 else
03943                                                                 {
03944                                                                         UWARN("Ignored texture %s (no image size set yet)", mesh->tex_materials[i].tex_file.c_str());
03945                                                                 }
03946                                                                 // relative path
03947                                                                 if(singleTexture)
03948                                                                 {
03949                                                                         mesh->tex_materials[i].tex_file=(prefix+ QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
03950                                                                 }
03951                                                                 else
03952                                                                 {
03953                                                                         mesh->tex_materials[i].tex_file=(currentPrefix+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
03954                                                                 }
03955                                                         }
03956                                                 }
03957                                                 pcl::PointCloud<pcl::PointNormal>::Ptr tmp(new pcl::PointCloud<pcl::PointNormal>);
03958                                                 pcl::fromPCLPointCloud2(mesh->cloud, *tmp);
03959                                                 tmp = util3d::transformPointCloud(tmp, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
03960                                                 pcl::toPCLPointCloud2(*tmp, mesh->cloud);
03961 
03962                                                 QString pathFile = path+QDir::separator()+QString("%1.%3").arg(currentPrefix).arg(suffix);
03963                                                 bool success =false;
03964                                                 if(suffix == "obj")
03965                                                 {
03966                                                         success = pcl::io::saveOBJFile(pathFile.toStdString(), *mesh) == 0;
03967                                                 }
03968                                                 else
03969                                                 {
03970                                                         UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
03971                                                 }
03972                                                 if(success)
03973                                                 {
03974                                                         _progressDialog->appendText(tr("Saved mesh %1 (%2 textures) to %3.")
03975                                                                         .arg(iter->first).arg(mesh->tex_materials.size()).arg(pathFile));
03976                                                 }
03977                                                 else
03978                                                 {
03979                                                         _progressDialog->appendText(tr("Failed saving mesh %1 (%2 textures) to %3.")
03980                                                                         .arg(iter->first).arg(mesh->tex_materials.size()).arg(pathFile), Qt::darkRed);
03981                                                         _progressDialog->setAutoClose(false);
03982                                                 }
03983                                         }
03984                                         else
03985                                         {
03986                                                 _progressDialog->appendText(tr("Mesh %1 is empty!").arg(iter->first));
03987                                         }
03988                                         _progressDialog->incrementStep();
03989                                         QApplication::processEvents();
03990                                         if(_canceled)
03991                                         {
03992                                                 return;
03993                                         }
03994                                 }
03995                         }
03996                 }
03997         }
03998 }
03999 
04000 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:19