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 "ExportCloudsDialog.h"
00029 #include "ui_exportCloudsDialog.h"
00030 
00031 #include "rtabmap/gui/ProgressDialog.h"
00032 #include "rtabmap/gui/CloudViewer.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 
00038 #include "rtabmap/core/util3d_filtering.h"
00039 #include "rtabmap/core/util3d_surface.h"
00040 #include "rtabmap/core/util3d_transforms.h"
00041 #include "rtabmap/core/util3d.h"
00042 #include "rtabmap/core/Graph.h"
00043 
00044 #include <pcl/conversions.h>
00045 #include <pcl/io/pcd_io.h>
00046 #include <pcl/io/ply_io.h>
00047 #include <pcl/io/vtk_io.h>
00048 #include <pcl/io/obj_io.h>
00049 
00050 #include <QPushButton>
00051 #include <QDir>
00052 #include <QFileInfo>
00053 #include <QMessageBox>
00054 #include <QFileDialog>
00055 #include <QInputDialog>
00056 
00057 namespace rtabmap {
00058 
00059 ExportCloudsDialog::ExportCloudsDialog(QWidget *parent) :
00060         QDialog(parent)
00061 {
00062         _ui = new Ui_ExportCloudsDialog();
00063         _ui->setupUi(this);
00064 
00065         connect(_ui->buttonBox->button(QDialogButtonBox::RestoreDefaults), SIGNAL(clicked()), this, SLOT(restoreDefaults()));
00066 
00067         restoreDefaults();
00068         _ui->comboBox_upsamplingMethod->setItemData(1, 0, Qt::UserRole - 1); // disable DISTINCT_CLOUD
00069 
00070         connect(_ui->checkBox_binary, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00071         connect(_ui->spinBox_normalKSearch, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00072         connect(_ui->comboBox_pipeline, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
00073         connect(_ui->comboBox_pipeline, SIGNAL(currentIndexChanged(int)), this, SLOT(updateReconstructionFlavor()));
00074 
00075         connect(_ui->groupBox_regenerate, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
00076         connect(_ui->spinBox_decimation, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00077         connect(_ui->doubleSpinBox_maxDepth, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00078         connect(_ui->doubleSpinBox_minDepth, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00079 
00080         connect(_ui->groupBox_filtering, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
00081         connect(_ui->doubleSpinBox_filteringRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00082         connect(_ui->spinBox_filteringMinNeighbors, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00083 
00084         connect(_ui->checkBox_assemble, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
00085         connect(_ui->doubleSpinBox_voxelSize_assembled, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00086 
00087         connect(_ui->groupBox_subtraction, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
00088         connect(_ui->doubleSpinBox_subtractPointFilteringRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00089         connect(_ui->doubleSpinBox_subtractPointFilteringAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00090         connect(_ui->spinBox_subtractFilteringMinPts, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00091 
00092         connect(_ui->groupBox_mls, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
00093         connect(_ui->doubleSpinBox_mlsRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00094         connect(_ui->spinBox_polygonialOrder, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00095         connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
00096         connect(_ui->doubleSpinBox_sampleStep, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00097         connect(_ui->spinBox_randomPoints, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00098         connect(_ui->doubleSpinBox_dilationVoxelSize, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00099         connect(_ui->spinBox_dilationSteps, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
00100         _ui->stackedWidget_upsampling->setCurrentIndex(_ui->comboBox_upsamplingMethod->currentIndex());
00101         connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_upsampling, SLOT(setCurrentIndex(int)));
00102         connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), this, SLOT(updateMLSGrpVisibility()));
00103         updateMLSGrpVisibility();
00104 
00105         connect(_ui->groupBox_meshing, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
00106         connect(_ui->doubleSpinBox_gp3Radius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00107         connect(_ui->doubleSpinBox_gp3Mu, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00108         connect(_ui->doubleSpinBox_meshDecimationFactor, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
00109         connect(_ui->checkBox_textureMapping, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
00110 
00111         _progressDialog = new ProgressDialog(this);
00112         _progressDialog->setVisible(false);
00113         _progressDialog->setAutoClose(true, 2);
00114         _progressDialog->setMinimumWidth(600);
00115 
00116 #ifdef DISABLE_VTK
00117         _ui->doubleSpinBox_meshDecimationFactor->setEnabled(false);
00118 #endif
00119 }
00120 
00121 ExportCloudsDialog::~ExportCloudsDialog()
00122 {
00123         delete _ui;
00124 }
00125 
00126 void ExportCloudsDialog::updateMLSGrpVisibility()
00127 {
00128         _ui->groupBox->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 0);
00129         _ui->groupBox_2->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 1);
00130         _ui->groupBox_3->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 2);
00131         _ui->groupBox_4->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 3);
00132         _ui->groupBox_5->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 4);
00133 }
00134 
00135 void ExportCloudsDialog::saveSettings(QSettings & settings, const QString & group) const
00136 {
00137         if(!group.isEmpty())
00138         {
00139                 settings.beginGroup(group);
00140         }
00141         settings.setValue("pipeline", _ui->comboBox_pipeline->currentIndex());
00142         settings.setValue("binary", _ui->checkBox_binary->isChecked());
00143         settings.setValue("normals_k", _ui->spinBox_normalKSearch->value());
00144 
00145         settings.setValue("regenerate", _ui->groupBox_regenerate->isChecked());
00146         settings.setValue("regenerate_decimation", _ui->spinBox_decimation->value());
00147         settings.setValue("regenerate_max_depth", _ui->doubleSpinBox_maxDepth->value());
00148         settings.setValue("regenerate_min_depth", _ui->doubleSpinBox_minDepth->value());
00149 
00150 
00151         settings.setValue("filtering", _ui->groupBox_filtering->isChecked());
00152         settings.setValue("filtering_radius", _ui->doubleSpinBox_filteringRadius->value());
00153         settings.setValue("filtering_min_neighbors", _ui->spinBox_filteringMinNeighbors->value());
00154 
00155         settings.setValue("assemble", _ui->checkBox_assemble->isChecked());
00156         settings.setValue("assemble_voxel",_ui->doubleSpinBox_voxelSize_assembled->value());
00157 
00158         settings.setValue("subtract",_ui->groupBox_subtraction->isChecked());
00159         settings.setValue("subtract_point_radius",_ui->doubleSpinBox_subtractPointFilteringRadius->value());
00160         settings.setValue("subtract_point_angle",_ui->doubleSpinBox_subtractPointFilteringAngle->value());
00161         settings.setValue("subtract_min_neighbors",_ui->spinBox_subtractFilteringMinPts->value());
00162 
00163         settings.setValue("mls", _ui->groupBox_mls->isChecked());
00164         settings.setValue("mls_radius", _ui->doubleSpinBox_mlsRadius->value());
00165         settings.setValue("mls_polygonial_order", _ui->spinBox_polygonialOrder->value());
00166         settings.setValue("mls_upsampling_method", _ui->comboBox_upsamplingMethod->currentIndex());
00167         settings.setValue("mls_upsampling_radius", _ui->doubleSpinBox_sampleRadius->value());
00168         settings.setValue("mls_upsampling_step", _ui->doubleSpinBox_sampleStep->value());
00169         settings.setValue("mls_point_density", _ui->spinBox_randomPoints->value());
00170         settings.setValue("mls_dilation_voxel_size", _ui->doubleSpinBox_dilationVoxelSize->value());
00171         settings.setValue("mls_dilation_iterations", _ui->spinBox_dilationSteps->value());
00172 
00173         settings.setValue("mesh", _ui->groupBox_meshing->isChecked());
00174         settings.setValue("mesh_radius", _ui->doubleSpinBox_gp3Radius->value());
00175         settings.setValue("mesh_mu", _ui->doubleSpinBox_gp3Mu->value());
00176         settings.setValue("mesh_decimation_factor", _ui->doubleSpinBox_meshDecimationFactor->value());
00177 
00178         settings.setValue("mesh_texture", _ui->checkBox_textureMapping->isChecked());
00179 
00180         settings.setValue("mesh_angle_tolerance", _ui->doubleSpinBox_mesh_angleTolerance->value());
00181         settings.setValue("mesh_quad", _ui->checkBox_mesh_quad->isChecked());
00182         settings.setValue("mesh_triangle_size", _ui->spinBox_mesh_triangleSize->value());
00183 
00184         if(!group.isEmpty())
00185         {
00186                 settings.endGroup();
00187         }
00188 }
00189 
00190 void ExportCloudsDialog::loadSettings(QSettings & settings, const QString & group)
00191 {
00192         if(!group.isEmpty())
00193         {
00194                 settings.beginGroup(group);
00195         }
00196 
00197         _ui->comboBox_pipeline->setCurrentIndex(settings.value("pipeline", _ui->comboBox_pipeline->currentIndex()).toInt());
00198         _ui->checkBox_binary->setChecked(settings.value("binary", _ui->checkBox_binary->isChecked()).toBool());
00199         _ui->spinBox_normalKSearch->setValue(settings.value("normals_k", _ui->spinBox_normalKSearch->value()).toInt());
00200 
00201         _ui->groupBox_regenerate->setChecked(settings.value("regenerate", _ui->groupBox_regenerate->isChecked()).toBool());
00202         _ui->spinBox_decimation->setValue(settings.value("regenerate_decimation", _ui->spinBox_decimation->value()).toInt());
00203         _ui->doubleSpinBox_maxDepth->setValue(settings.value("regenerate_max_depth", _ui->doubleSpinBox_maxDepth->value()).toDouble());
00204         _ui->doubleSpinBox_minDepth->setValue(settings.value("regenerate_min_depth", _ui->doubleSpinBox_minDepth->value()).toDouble());
00205 
00206         _ui->groupBox_filtering->setChecked(settings.value("filtering", _ui->groupBox_filtering->isChecked()).toBool());
00207         _ui->doubleSpinBox_filteringRadius->setValue(settings.value("filtering_radius", _ui->doubleSpinBox_filteringRadius->value()).toDouble());
00208         _ui->spinBox_filteringMinNeighbors->setValue(settings.value("filtering_min_neighbors", _ui->spinBox_filteringMinNeighbors->value()).toInt());
00209 
00210         _ui->checkBox_assemble->setChecked(settings.value("assemble", _ui->checkBox_assemble->isChecked()).toBool());
00211         _ui->doubleSpinBox_voxelSize_assembled->setValue(settings.value("assemble_voxel", _ui->doubleSpinBox_voxelSize_assembled->value()).toDouble());
00212 
00213         _ui->groupBox_subtraction->setChecked(settings.value("subtract",_ui->groupBox_subtraction->isChecked()).toBool());
00214         _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(settings.value("subtract_point_radius",_ui->doubleSpinBox_subtractPointFilteringRadius->value()).toDouble());
00215         _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(settings.value("subtract_point_angle",_ui->doubleSpinBox_subtractPointFilteringAngle->value()).toDouble());
00216         _ui->spinBox_subtractFilteringMinPts->setValue(settings.value("subtract_min_neighbors",_ui->spinBox_subtractFilteringMinPts->value()).toInt());
00217 
00218         _ui->groupBox_mls->setChecked(settings.value("mls", _ui->groupBox_mls->isChecked()).toBool());
00219         _ui->doubleSpinBox_mlsRadius->setValue(settings.value("mls_radius", _ui->doubleSpinBox_mlsRadius->value()).toDouble());
00220         _ui->spinBox_polygonialOrder->setValue(settings.value("mls_polygonial_order", _ui->spinBox_polygonialOrder->value()).toInt());
00221         _ui->comboBox_upsamplingMethod->setCurrentIndex(settings.value("mls_upsampling_method", _ui->comboBox_upsamplingMethod->currentIndex()).toInt());
00222         _ui->doubleSpinBox_sampleRadius->setValue(settings.value("mls_upsampling_radius", _ui->doubleSpinBox_sampleRadius->value()).toDouble());
00223         _ui->doubleSpinBox_sampleStep->setValue(settings.value("mls_upsampling_step", _ui->doubleSpinBox_sampleStep->value()).toDouble());
00224         _ui->spinBox_randomPoints->setValue(settings.value("mls_point_density", _ui->spinBox_randomPoints->value()).toInt());
00225         _ui->doubleSpinBox_dilationVoxelSize->setValue(settings.value("mls_dilation_voxel_size", _ui->doubleSpinBox_dilationVoxelSize->value()).toDouble());
00226         _ui->spinBox_dilationSteps->setValue(settings.value("mls_dilation_iterations", _ui->spinBox_dilationSteps->value()).toInt());
00227 
00228         _ui->groupBox_meshing->setChecked(settings.value("mesh", _ui->groupBox_meshing->isChecked()).toBool());
00229         _ui->doubleSpinBox_gp3Radius->setValue(settings.value("mesh_radius", _ui->doubleSpinBox_gp3Radius->value()).toDouble());
00230         _ui->doubleSpinBox_gp3Mu->setValue(settings.value("mesh_mu", _ui->doubleSpinBox_gp3Mu->value()).toDouble());
00231         _ui->doubleSpinBox_meshDecimationFactor->setValue(settings.value("mesh_decimation_factor",_ui->doubleSpinBox_meshDecimationFactor->value()).toDouble());
00232 
00233         _ui->checkBox_textureMapping->setChecked(settings.value("mesh_texture", _ui->checkBox_textureMapping->isChecked()).toBool());
00234 
00235         _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value("mesh_angle_tolerance", _ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
00236         _ui->checkBox_mesh_quad->setChecked(settings.value("mesh_quad", _ui->checkBox_mesh_quad->isChecked()).toBool());
00237         _ui->spinBox_mesh_triangleSize->setValue(settings.value("mesh_triangle_size", _ui->spinBox_mesh_triangleSize->value()).toInt());
00238 
00239         if(!group.isEmpty())
00240         {
00241                 settings.endGroup();
00242         }
00243 }
00244 
00245 void ExportCloudsDialog::restoreDefaults()
00246 {
00247         _ui->checkBox_binary->setChecked(true);
00248         _ui->spinBox_normalKSearch->setValue(10);
00249 
00250         _ui->groupBox_regenerate->setChecked(false);
00251         _ui->spinBox_decimation->setValue(1);
00252         _ui->doubleSpinBox_maxDepth->setValue(4);
00253         _ui->doubleSpinBox_minDepth->setValue(0);
00254 
00255         _ui->groupBox_filtering->setChecked(false);
00256         _ui->doubleSpinBox_filteringRadius->setValue(0.02);
00257         _ui->spinBox_filteringMinNeighbors->setValue(2);
00258 
00259         _ui->checkBox_assemble->setChecked(true);
00260         _ui->doubleSpinBox_voxelSize_assembled->setValue(0.0);
00261 
00262         _ui->groupBox_subtraction->setChecked(false);
00263         _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(0.02);
00264         _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(0);
00265         _ui->spinBox_subtractFilteringMinPts->setValue(5);
00266 
00267         _ui->groupBox_mls->setChecked(false);
00268         _ui->doubleSpinBox_mlsRadius->setValue(0.04);
00269         _ui->spinBox_polygonialOrder->setValue(2);
00270         _ui->comboBox_upsamplingMethod->setCurrentIndex(0);
00271         _ui->doubleSpinBox_sampleRadius->setValue(0.01);
00272         _ui->doubleSpinBox_sampleStep->setValue(0.0);
00273         _ui->spinBox_randomPoints->setValue(0);
00274         _ui->doubleSpinBox_dilationVoxelSize->setValue(0.01);
00275         _ui->spinBox_dilationSteps->setValue(0);
00276 
00277         _ui->groupBox_meshing->setChecked(false);
00278         _ui->doubleSpinBox_gp3Radius->setValue(0.04);
00279         _ui->doubleSpinBox_gp3Mu->setValue(2.5);
00280         _ui->doubleSpinBox_meshDecimationFactor->setValue(0.0);
00281 
00282         _ui->checkBox_textureMapping->setChecked(false);
00283 
00284         _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
00285         _ui->checkBox_mesh_quad->setChecked(false);
00286         _ui->spinBox_mesh_triangleSize->setValue(2);
00287 
00288         updateReconstructionFlavor();
00289 
00290         this->update();
00291 }
00292 
00293 void ExportCloudsDialog::updateReconstructionFlavor()
00294 {
00295         _ui->groupBox_mls->setVisible(_ui->comboBox_pipeline->currentIndex() == 1);
00296         _ui->groupBox_gp3->setVisible(_ui->comboBox_pipeline->currentIndex() == 1);
00297         _ui->groupBox_organized->setVisible(_ui->comboBox_pipeline->currentIndex() == 0);
00298 }
00299 
00300 void ExportCloudsDialog::setSaveButton()
00301 {
00302         _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(false);
00303         _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(true);
00304         _ui->checkBox_binary->setVisible(true);
00305         _ui->label_binaryFile->setVisible(true);
00306         _ui->checkBox_textureMapping->setVisible(true);
00307         _ui->checkBox_textureMapping->setEnabled(true);
00308         _ui->label_textureMapping->setVisible(true);
00309         _ui->checkBox_mesh_quad->setVisible(false);
00310         _ui->checkBox_mesh_quad->setEnabled(false);
00311         _ui->label_quad->setVisible(false);
00312 }
00313 
00314 void ExportCloudsDialog::setOkButton()
00315 {
00316         _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(true);
00317         _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(false);
00318         _ui->checkBox_binary->setVisible(false);
00319         _ui->label_binaryFile->setVisible(false);
00320         _ui->checkBox_textureMapping->setVisible(false);
00321         _ui->checkBox_textureMapping->setEnabled(false);
00322         _ui->label_textureMapping->setVisible(false);
00323         _ui->checkBox_mesh_quad->setVisible(true);
00324         _ui->checkBox_mesh_quad->setEnabled(true);
00325         _ui->label_quad->setVisible(true);
00326 }
00327 
00328 void ExportCloudsDialog::enableRegeneration(bool enabled)
00329 {
00330         if(!enabled)
00331         {
00332                 _ui->groupBox_regenerate->setChecked(false);
00333         }
00334         _ui->groupBox_regenerate->setEnabled(enabled);
00335 }
00336 
00337 void ExportCloudsDialog::exportClouds(
00338                 const std::map<int, Transform> & poses,
00339                 const std::map<int, int> & mapIds,
00340                 const QMap<int, Signature> & cachedSignatures,
00341                 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
00342                 const QString & workingDirectory,
00343                 const ParametersMap & parameters)
00344 {
00345         std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
00346         std::map<int, pcl::PolygonMesh::Ptr> meshes;
00347         std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
00348 
00349         setSaveButton();
00350 
00351         if(getExportedClouds(
00352                         poses,
00353                         mapIds,
00354                         cachedSignatures,
00355                         cachedClouds,
00356                         workingDirectory,
00357                         parameters,
00358                         clouds,
00359                         meshes,
00360                         textureMeshes))
00361         {
00362                 if(textureMeshes.size())
00363                 {
00364                         saveTextureMeshes(workingDirectory, poses, textureMeshes);
00365                 }
00366                 else if(meshes.size())
00367                 {
00368                         bool exportMeshes = true;
00369                         if(_ui->checkBox_textureMapping->isChecked())
00370                         {
00371                                 QMessageBox::StandardButton r = QMessageBox::warning(this, tr("Exporting Texture Mesh"),
00372                                                 tr("No texture mesh could be created, do you want to continue with saving only the meshes (%1)?").arg(meshes.size()),
00373                                                 QMessageBox::Yes|QMessageBox::No, QMessageBox::Yes);
00374                                 exportMeshes = r == QMessageBox::Yes;
00375                         }
00376                         if(exportMeshes)
00377                         {
00378                                 saveMeshes(workingDirectory, poses, meshes, _ui->checkBox_binary->isChecked());
00379                         }
00380                 }
00381                 else
00382                 {
00383                         saveClouds(workingDirectory, poses, clouds, _ui->checkBox_binary->isChecked());
00384                 }
00385                 _progressDialog->setValue(_progressDialog->maximumSteps());
00386         }
00387 }
00388 
00389 void ExportCloudsDialog::viewClouds(
00390                 const std::map<int, Transform> & poses,
00391                 const std::map<int, int> & mapIds,
00392                 const QMap<int, Signature> & cachedSignatures,
00393                 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
00394                 const QString & workingDirectory,
00395                 const ParametersMap & parameters)
00396 {
00397         std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
00398         std::map<int, pcl::PolygonMesh::Ptr> meshes;
00399         std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
00400 
00401         setOkButton();
00402 
00403         if(getExportedClouds(
00404                         poses,
00405                         mapIds,
00406                         cachedSignatures,
00407                         cachedClouds,
00408                         workingDirectory,
00409                         parameters,
00410                         clouds,
00411                         meshes,
00412                         textureMeshes))
00413         {
00414                 QDialog * window = new QDialog(this->parentWidget()?this->parentWidget():this, Qt::Window);
00415                 window->setAttribute(Qt::WA_DeleteOnClose, true);
00416                 if(meshes.size())
00417                 {
00418                         window->setWindowTitle(tr("Meshes (%1 nodes)").arg(meshes.size()));
00419                 }
00420                 else
00421                 {
00422                         window->setWindowTitle(tr("Clouds (%1 nodes)").arg(clouds.size()));
00423                 }
00424                 window->setMinimumWidth(800);
00425                 window->setMinimumHeight(600);
00426 
00427                 CloudViewer * viewer = new CloudViewer(window);
00428                 viewer->setCameraLockZ(false);
00429                 if(_ui->comboBox_pipeline->currentIndex() == 0)
00430                 {
00431                         viewer->setBackfaceCulling(true, false);
00432                 }
00433 
00434                 QVBoxLayout *layout = new QVBoxLayout();
00435                 layout->addWidget(viewer);
00436                 window->setLayout(layout);
00437                 connect(window, SIGNAL(finished(int)), viewer, SLOT(clear()));
00438 
00439                 window->show();
00440 
00441                 uSleep(500);
00442 
00443                 if(meshes.size())
00444                 {
00445                         for(std::map<int, pcl::PolygonMesh::Ptr>::iterator iter = meshes.begin(); iter!=meshes.end(); ++iter)
00446                         {
00447                                 _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)...").arg(iter->first).arg(iter->second->polygons.size()));
00448                                 _progressDialog->incrementStep();
00449                                 bool isRGB = false;
00450                                 for(unsigned int i=0; i<iter->second->cloud.fields.size(); ++i)
00451                                 {
00452                                         if(iter->second->cloud.fields[i].name.compare("rgb") == 0)
00453                                         {
00454                                                 isRGB=true;
00455                                                 break;
00456                                         }
00457                                 }
00458                                 if(isRGB)
00459                                 {
00460                                         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00461                                         pcl::fromPCLPointCloud2(iter->second->cloud, *cloud);
00462                                         viewer->addCloudMesh(uFormat("mesh%d",iter->first), cloud, iter->second->polygons, iter->first>0?poses.at(iter->first):Transform::getIdentity());
00463                                 }
00464                                 else
00465                                 {
00466                                         pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
00467                                         pcl::fromPCLPointCloud2(iter->second->cloud, *cloud);
00468                                         viewer->addCloudMesh(uFormat("mesh%d",iter->first), cloud, iter->second->polygons, iter->first>0?poses.at(iter->first):Transform::getIdentity());
00469                                 }
00470                                 _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)... done.").arg(iter->first).arg(iter->second->polygons.size()));
00471                                 QApplication::processEvents();
00472                         }
00473                 }
00474                 else if(clouds.size())
00475                 {
00476                         for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::iterator iter = clouds.begin(); iter!=clouds.end(); ++iter)
00477                         {
00478                                 _progressDialog->appendText(tr("Viewing the cloud %1 (%2 points)...").arg(iter->first).arg(iter->second->size()));
00479                                 _progressDialog->incrementStep();
00480 
00481                                 QColor color = Qt::gray;
00482                                 int mapId = uValue(mapIds, iter->first, -1);
00483                                 if(mapId >= 0)
00484                                 {
00485                                         color = (Qt::GlobalColor)(mapId % 12 + 7 );
00486                                 }
00487                                 viewer->addCloud(uFormat("cloud%d",iter->first), iter->second, iter->first>0?poses.at(iter->first):Transform::getIdentity());
00488                                 _progressDialog->appendText(tr("Viewing the cloud %1 (%2 points)... done.").arg(iter->first).arg(iter->second->size()));
00489                         }
00490                 }
00491 
00492                 _progressDialog->setValue(_progressDialog->maximumSteps());
00493                 viewer->update();
00494         }
00495 }
00496 
00497 bool removeDirRecursively(const QString & dirName)
00498 {
00499     bool result = true;
00500     QDir dir(dirName);
00501 
00502     if (dir.exists(dirName)) {
00503         Q_FOREACH(QFileInfo info, dir.entryInfoList(QDir::NoDotAndDotDot | QDir::System | QDir::Hidden  | QDir::AllDirs | QDir::Files, QDir::DirsFirst)) {
00504             if (info.isDir()) {
00505                 result = removeDirRecursively(info.absoluteFilePath());
00506             }
00507             else {
00508                 result = QFile::remove(info.absoluteFilePath());
00509             }
00510 
00511             if (!result) {
00512                 return result;
00513             }
00514         }
00515         result = dir.rmdir(dirName);
00516     }
00517     return result;
00518 }
00519 
00520 bool ExportCloudsDialog::getExportedClouds(
00521                 const std::map<int, Transform> & poses,
00522                 const std::map<int, int> & mapIds,
00523                 const QMap<int, Signature> & cachedSignatures,
00524                 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
00525                 const QString & workingDirectory,
00526                 const ParametersMap & parameters,
00527                 std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & cloudsWithNormals,
00528                 std::map<int, pcl::PolygonMesh::Ptr> & meshes,
00529                 std::map<int, pcl::TextureMesh::Ptr> & textureMeshes)
00530 {
00531         enableRegeneration(cachedSignatures.size());
00532         if(this->exec() == QDialog::Accepted)
00533         {
00534                 _progressDialog->resetProgress();
00535                 _progressDialog->show();
00536                 int mul = 1;
00537                 if(_ui->groupBox_meshing->isChecked())
00538                 {
00539                         mul+=1;
00540                 }
00541                 if(_ui->checkBox_assemble->isChecked())
00542                 {
00543                         mul+=1;
00544                 }
00545 
00546                 if(_ui->groupBox_subtraction->isChecked())
00547                 {
00548                         mul+=1;
00549                 }
00550                 mul+=1; // normals
00551                 if(_ui->checkBox_textureMapping->isChecked())
00552                 {
00553                         mul+=1;
00554                 }
00555                 _progressDialog->setMaximumSteps(int(poses.size())*mul+1);
00556 
00557                 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds = this->getClouds(
00558                                 poses,
00559                                 cachedSignatures,
00560                                 cachedClouds,
00561                                 parameters);
00562 
00563                 pcl::PointCloud<pcl::PointXYZ>::Ptr rawAssembledCloud(new pcl::PointCloud<pcl::PointXYZ>);
00564                 std::vector<int> rawCameraIndices;
00565                 if(_ui->checkBox_assemble->isChecked() &&
00566                    !(_ui->comboBox_pipeline->currentIndex()==0 && _ui->groupBox_meshing->isChecked()))
00567                 {
00568                         _progressDialog->appendText(tr("Assembling %1 clouds...").arg(clouds.size()));
00569                         QApplication::processEvents();
00570 
00571                         int i =0;
00572                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr assembledCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00573                         for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator iter=clouds.begin();
00574                                 iter!= clouds.end();
00575                                 ++iter)
00576                         {
00577                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformed(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00578                                 if(iter->second.first->isOrganized())
00579                                 {
00580                                         pcl::copyPointCloud(*iter->second.first, *iter->second.second, *transformed);
00581                                         transformed = util3d::transformPointCloud(transformed, poses.at(iter->first));
00582                                 }
00583                                 else
00584                                 {
00585                                         transformed = util3d::transformPointCloud(iter->second.first, poses.at(iter->first));
00586                                 }
00587 
00588                                 *assembledCloud += *transformed;
00589                                 rawCameraIndices.resize(assembledCloud->size(), iter->first);
00590 
00591                                 _progressDialog->appendText(tr("Assembled cloud %1, total=%2 (%3/%4).").arg(iter->first).arg(assembledCloud->size()).arg(++i).arg(clouds.size()));
00592                                 _progressDialog->incrementStep();
00593                                 QApplication::processEvents();
00594                         }
00595 
00596                         pcl::copyPointCloud(*assembledCloud, *rawAssembledCloud);
00597 
00598                         if(_ui->doubleSpinBox_voxelSize_assembled->value())
00599                         {
00600                                 _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...")
00601                                                 .arg(assembledCloud->size())
00602                                                 .arg(_ui->doubleSpinBox_voxelSize_assembled->value()));
00603                                 QApplication::processEvents();
00604                                 assembledCloud = util3d::voxelize(
00605                                                 assembledCloud,
00606                                                 _ui->doubleSpinBox_voxelSize_assembled->value());
00607                         }
00608 
00609                         clouds.clear();
00610                         clouds.insert(std::make_pair(0, std::make_pair(assembledCloud, pcl::IndicesPtr(new std::vector<int>))));
00611                 }
00612 
00613                 std::map<int, Transform> viewPoints = poses;
00614                 if(_ui->groupBox_mls->isChecked())
00615                 {
00616                         _progressDialog->appendText(tr("Smoothing the surface using Moving Least Squares (MLS) algorithm... "
00617                                         "[search radius=%1m voxel=%2m]").arg(_ui->doubleSpinBox_mlsRadius->value()).arg(_ui->doubleSpinBox_voxelSize_assembled->value()));
00618                         QApplication::processEvents();
00619                         QApplication::processEvents();
00620 
00621                         // Adjust view points with local transforms
00622                         for(std::map<int, Transform>::iterator iter= viewPoints.begin(); iter!=viewPoints.end(); ++iter)
00623                         {
00624                                 if(cachedSignatures.contains(iter->first))
00625                                 {
00626                                         const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
00627                                         if(data.cameraModels().size() && !data.cameraModels()[0].localTransform().isNull())
00628                                         {
00629                                                 iter->second *= data.cameraModels()[0].localTransform();
00630                                         }
00631                                         else if(!data.stereoCameraModel().localTransform().isNull())
00632                                         {
00633                                                 iter->second *= data.stereoCameraModel().localTransform();
00634                                         }
00635                                 }
00636                         }
00637                 }
00638 
00639                 //fill cloudWithNormals
00640                 for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator iter=clouds.begin();
00641                         iter!= clouds.end();
00642                         ++iter)
00643                 {
00644                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudWithNormals = iter->second.first;
00645 
00646                         if(_ui->groupBox_mls->isChecked())
00647                         {
00648                                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals(new pcl::PointCloud<pcl::PointXYZRGB>);
00649                                 if(iter->second.first->isOrganized())
00650                                 {
00651                                         pcl::copyPointCloud(*cloudWithNormals, *iter->second.second, *cloudWithoutNormals);
00652                                 }
00653                                 else
00654                                 {
00655                                         pcl::copyPointCloud(*cloudWithNormals, *cloudWithoutNormals);
00656                                 }
00657 
00658                                 _progressDialog->appendText(tr("Smoothing (MLS) the cloud (%1 points)...").arg(cloudWithNormals->size()));
00659                                 QApplication::processEvents();
00660 
00661                                 cloudWithNormals = util3d::mls(
00662                                                 cloudWithoutNormals,
00663                                                 (float)_ui->doubleSpinBox_mlsRadius->value(),
00664                                                 _ui->spinBox_polygonialOrder->value(),
00665                                                 _ui->comboBox_upsamplingMethod->currentIndex(),
00666                                                 (float)_ui->doubleSpinBox_sampleRadius->value(),
00667                                                 (float)_ui->doubleSpinBox_sampleStep->value(),
00668                                                 _ui->spinBox_randomPoints->value(),
00669                                                 (float)_ui->doubleSpinBox_dilationVoxelSize->value(),
00670                                                 _ui->spinBox_dilationSteps->value());
00671 
00672                                 if(_ui->checkBox_assemble->isChecked())
00673                                 {
00674                                         // Re-voxelize to make sure to have uniform density
00675                                         if(_ui->doubleSpinBox_voxelSize_assembled->value())
00676                                         {
00677                                                 _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...")
00678                                                                 .arg(cloudWithNormals->size())
00679                                                                 .arg(_ui->doubleSpinBox_voxelSize_assembled->value()));
00680                                                 QApplication::processEvents();
00681 
00682                                                 cloudWithNormals = util3d::voxelize(
00683                                                                 cloudWithNormals,
00684                                                                 _ui->doubleSpinBox_voxelSize_assembled->value());
00685                                         }
00686                                 
00687                                         _progressDialog->appendText(tr("Update %1 normals with %2 camera views...").arg(cloudWithNormals->size()).arg(poses.size()));
00688 
00689                                         util3d::adjustNormalsToViewPoints(
00690                                                         viewPoints,
00691                                                         rawAssembledCloud,
00692                                                         rawCameraIndices,
00693                                                         cloudWithNormals);
00694                                 }
00695                         }
00696                         else if(iter->second.first->isOrganized() && _ui->groupBox_filtering->isChecked())
00697                         {
00698                                 cloudWithNormals = util3d::extractIndices(iter->second.first, iter->second.second, false, true);
00699                         }
00700 
00701                         cloudsWithNormals.insert(std::make_pair(iter->first, cloudWithNormals));
00702 
00703                         _progressDialog->incrementStep();
00704                         QApplication::processEvents();
00705                 }
00706 
00707                 //used for organized texturing below
00708                 std::map<int, std::pair<std::map<int, int>, std::pair<int, int> > > organizedIndices;
00709 
00710                 //mesh
00711                 UDEBUG("Meshing=%d", _ui->groupBox_meshing->isChecked()?1:0);
00712                 if(_ui->groupBox_meshing->isChecked())
00713                 {
00714                         if(_ui->comboBox_pipeline->currentIndex() == 0)
00715                         {
00716                                 _progressDialog->appendText(tr("Organized fast mesh... "));
00717                                 QApplication::processEvents();
00718                                 QApplication::processEvents();
00719 
00720                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00721                                 std::vector<pcl::Vertices> mergedPolygons;
00722 
00723                                 int i=0;
00724                                 for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::iterator iter=cloudsWithNormals.begin();
00725                                         iter!= cloudsWithNormals.end();
00726                                         ++iter)
00727                                 {
00728                                         if(iter->second->isOrganized())
00729                                         {
00730                                                 if(iter->second->size())
00731                                                 {
00732                                                         Eigen::Vector3f viewpoint(0.0f,0.0f,0.0f);
00733                                                         if(cachedSignatures.contains(iter->first))
00734                                                         {
00735                                                                 const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
00736                                                                 if(data.cameraModels().size() && !data.cameraModels()[0].localTransform().isNull())
00737                                                                 {
00738                                                                         viewpoint[0] = data.cameraModels()[0].localTransform().x();
00739                                                                         viewpoint[1] = data.cameraModels()[0].localTransform().y();
00740                                                                         viewpoint[2] = data.cameraModels()[0].localTransform().z();
00741                                                                 }
00742                                                                 else if(!data.stereoCameraModel().localTransform().isNull())
00743                                                                 {
00744                                                                         viewpoint[0] = data.stereoCameraModel().localTransform().x();
00745                                                                         viewpoint[1] = data.stereoCameraModel().localTransform().y();
00746                                                                         viewpoint[2] = data.stereoCameraModel().localTransform().z();
00747                                                                 }
00748                                                         }
00749                                                         std::vector<pcl::Vertices> polygons = util3d::organizedFastMesh(
00750                                                                         iter->second,
00751                                                                         _ui->doubleSpinBox_mesh_angleTolerance->value()*M_PI/180.0,
00752                                                                         _ui->checkBox_mesh_quad->isEnabled() && _ui->checkBox_mesh_quad->isChecked(),
00753                                                                         _ui->spinBox_mesh_triangleSize->value(),
00754                                                                         viewpoint);
00755                                                         _progressDialog->appendText(tr("Mesh %1 created with %2 polygons (%3/%4).").arg(iter->first).arg(polygons.size()).arg(++i).arg(clouds.size()));
00756 
00757                                                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr denseCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00758                                                         std::vector<pcl::Vertices> densePolygons;
00759                                                         std::map<int, int> newToOldIndices = util3d::filterNotUsedVerticesFromMesh(*iter->second, polygons, *denseCloud, densePolygons);
00760 
00761                                                         if(!_ui->checkBox_assemble->isChecked() ||
00762                                                                  (_ui->checkBox_textureMapping->isEnabled() &&
00763                                                                   _ui->checkBox_textureMapping->isChecked() &&
00764                                                                   _ui->doubleSpinBox_voxelSize_assembled->value() == 0.0)) // don't assemble now if we are texturing
00765                                                         {
00766                                                                 if(_ui->checkBox_assemble->isChecked())
00767                                                                 {
00768                                                                         denseCloud = util3d::transformPointCloud(denseCloud, poses.at(iter->first));
00769                                                                 }
00770 
00771                                                                 pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
00772                                                                 pcl::toPCLPointCloud2(*denseCloud, mesh->cloud);
00773                                                                 mesh->polygons = densePolygons;
00774                                                                 if(_ui->doubleSpinBox_meshDecimationFactor->isEnabled() &&
00775                                                                    _ui->doubleSpinBox_meshDecimationFactor->value() > 0.0)
00776                                                                 {
00777                                                                         int count = mesh->polygons.size();
00778                                                                         mesh = util3d::meshDecimation(mesh, (float)_ui->doubleSpinBox_meshDecimationFactor->value());
00779                                                                         _progressDialog->appendText(tr("Mesh decimation (factor=%1) from %2 to %3 polygons").arg(_ui->doubleSpinBox_meshDecimationFactor->value()).arg(count).arg(mesh->polygons.size()));
00780                                                                 }
00781                                                                 else
00782                                                                 {
00783                                                                         organizedIndices.insert(std::make_pair(iter->first, std::make_pair(newToOldIndices, std::make_pair(iter->second->width, iter->second->height))));
00784                                                                 }
00785                                                                 meshes.insert(std::make_pair(iter->first, mesh));
00786                                                         }
00787                                                         else
00788                                                         {
00789                                                                 denseCloud = util3d::transformPointCloud(denseCloud, poses.at(iter->first));
00790                                                                 if(mergedClouds->size() == 0)
00791                                                                 {
00792                                                                         *mergedClouds = *denseCloud;
00793                                                                         mergedPolygons = densePolygons;
00794                                                                 }
00795                                                                 else
00796                                                                 {
00797                                                                         util3d::appendMesh(*mergedClouds, mergedPolygons, *denseCloud, densePolygons);
00798                                                                 }
00799                                                         }
00800                                                 }
00801                                                 else
00802                                                 {
00803                                                         _progressDialog->appendText(tr("Mesh %1 not created (no valid points) (%2/%3).").arg(iter->first).arg(++i).arg(clouds.size()));
00804                                                 }
00805                                         }
00806                                         else
00807                                         {
00808                                                 _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(++i).arg(clouds.size()));
00809                                         }
00810 
00811                                         _progressDialog->incrementStep();
00812                                         QApplication::processEvents();
00813                                 }
00814 
00815                                 if(_ui->checkBox_assemble->isChecked() && mergedClouds->size())
00816                                 {
00817                                         if(_ui->doubleSpinBox_voxelSize_assembled->value())
00818                                         {
00819                                                 _progressDialog->appendText(tr("Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").arg(mergedClouds->size()).arg(mergedPolygons.size()));
00820                                                 QApplication::processEvents();
00821 
00822                                                 mergedPolygons = util3d::filterCloseVerticesFromMesh(
00823                                                                 mergedClouds,
00824                                                                 mergedPolygons,
00825                                                                 _ui->doubleSpinBox_voxelSize_assembled->value(),
00826                                                                 M_PI/4,
00827                                                                 true);
00828 
00829                                                 // filter invalid polygons
00830                                                 unsigned int count = mergedPolygons.size();
00831                                                 mergedPolygons = util3d::filterInvalidPolygons(mergedPolygons);
00832                                                 _progressDialog->appendText(tr("Filtered %1 invalid polygons.").arg(count-mergedPolygons.size()));
00833                                                 QApplication::processEvents();
00834 
00835                                                 // filter not used vertices
00836                                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00837                                                 std::vector<pcl::Vertices> filteredPolygons;
00838                                                 util3d::filterNotUsedVerticesFromMesh(*mergedClouds, mergedPolygons, *filteredCloud, filteredPolygons);
00839                                                 mergedClouds = filteredCloud;
00840                                                 mergedPolygons = filteredPolygons;
00841                                         }
00842 
00843                                         pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
00844                                         pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
00845                                         mesh->polygons = mergedPolygons;
00846 
00847                                         if(_ui->doubleSpinBox_meshDecimationFactor->isEnabled() &&
00848                                            _ui->doubleSpinBox_meshDecimationFactor->value() > 0.0)
00849                                         {
00850                                                 int count = mesh->polygons.size();
00851                                                 mesh = util3d::meshDecimation(mesh, (float)_ui->doubleSpinBox_meshDecimationFactor->value());
00852                                                 _progressDialog->appendText(tr("Assembled mesh decimation (factor=%1) from %2 to %3 polygons").arg(_ui->doubleSpinBox_meshDecimationFactor->value()).arg(count).arg(mesh->polygons.size()));
00853                                         }
00854 
00855                                         meshes.insert(std::make_pair(0, mesh));
00856 
00857                                         _progressDialog->incrementStep();
00858                                         QApplication::processEvents();
00859                                 }
00860 
00861                         }
00862                         else
00863                         {
00864                                 _progressDialog->appendText(tr("Greedy projection triangulation... [radius=%1m]").arg(_ui->doubleSpinBox_gp3Radius->value()));
00865                                 QApplication::processEvents();
00866                                 QApplication::processEvents();
00867 
00868                                 int i=0;
00869                                 for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::iterator iter=cloudsWithNormals.begin();
00870                                         iter!= cloudsWithNormals.end();
00871                                         ++iter)
00872                                 {
00873                                         pcl::PolygonMesh::Ptr mesh = util3d::createMesh(
00874                                                         iter->second,
00875                                                         _ui->doubleSpinBox_gp3Radius->value(),
00876                                                         _ui->doubleSpinBox_gp3Mu->value());
00877                                         _progressDialog->appendText(tr("Mesh %1 created with %2 polygons (%3/%4).").arg(iter->first).arg(mesh->polygons.size()).arg(++i).arg(clouds.size()));
00878                                         QApplication::processEvents();
00879 
00880                                         if(_ui->doubleSpinBox_meshDecimationFactor->isEnabled() &&
00881                                            _ui->doubleSpinBox_meshDecimationFactor->value() > 0.0)
00882                                         {
00883                                                 int count = mesh->polygons.size();
00884                                                 mesh = util3d::meshDecimation(mesh, (float)_ui->doubleSpinBox_meshDecimationFactor->value());
00885                                                 _progressDialog->appendText(tr("Assembled mesh decimation (factor=%1) from %2 to %3 polygons").arg(_ui->doubleSpinBox_meshDecimationFactor->value()).arg(count).arg(mesh->polygons.size()));
00886                                         }
00887 
00888                                         meshes.insert(std::make_pair(iter->first, mesh));
00889 
00890                                         _progressDialog->incrementStep();
00891                                         QApplication::processEvents();
00892                                 }
00893                         }
00894                 }
00895 
00896                 // texture mesh
00897                 UDEBUG("texture mapping=%d", _ui->checkBox_textureMapping->isChecked()?1:0);
00898                 if(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked())
00899                 {
00900                         QDir dir(workingDirectory);
00901                         removeDirRecursively(workingDirectory+QDir::separator()+"tmp_textures");
00902                         dir.mkdir("tmp_textures");
00903                         int i=0;
00904                         for(std::map<int, pcl::PolygonMesh::Ptr>::iterator iter=meshes.begin();
00905                                 iter!= meshes.end();
00906                                 ++iter)
00907                         {
00908                                 std::map<int, Transform> cameras;
00909                                 if(iter->first == 0)
00910                                 {
00911                                         cameras = poses;
00912                                 }
00913                                 else
00914                                 {
00915                                         UASSERT(uContains(poses, iter->first));
00916                                         cameras.insert(std::make_pair(iter->first, _ui->checkBox_assemble->isChecked()?poses.at(iter->first):Transform::getIdentity()));
00917                                 }
00918                                 std::map<int, Transform> cameraPoses;
00919                                 std::map<int, CameraModel> cameraModels;
00920                                 std::map<int, cv::Mat> images;
00921                                 for(std::map<int, Transform>::iterator jter=cameras.begin(); jter!=cameras.end(); ++jter)
00922                                 {
00923                                         if(cachedSignatures.contains(jter->first))
00924                                         {
00925                                                 const Signature & s = cachedSignatures.value(jter->first);
00926                                                 CameraModel model;
00927                                                 if(s.sensorData().stereoCameraModel().isValidForProjection())
00928                                                 {
00929                                                         model = s.sensorData().stereoCameraModel().left();
00930                                                 }
00931                                                 else if(s.sensorData().cameraModels().size() == 1 && s.sensorData().cameraModels()[0].isValidForProjection())
00932                                                 {
00933                                                         model = s.sensorData().cameraModels()[0];
00934                                                 }
00935                                                 cv::Mat image = s.sensorData().imageRaw();
00936                                                 if(image.empty() && !s.sensorData().imageCompressed().empty())
00937                                                 {
00938                                                         s.sensorData().uncompressDataConst(&image, 0, 0, 0);
00939                                                 }
00940                                                 if(!jter->second.isNull() && model.isValidForProjection() && !image.empty())
00941                                                 {
00942                                                         cameraPoses.insert(std::make_pair(jter->first, jter->second));
00943                                                         cameraModels.insert(std::make_pair(jter->first, model));
00944                                                         images.insert(std::make_pair(jter->first, image));
00945                                                 }
00946                                         }
00947                                 }
00948                                 if(cameraPoses.size())
00949                                 {
00950                                         pcl::TextureMesh::Ptr textureMesh(new pcl::TextureMesh);
00951                                         std::map<int, std::pair<std::map<int, int>, std::pair<int, int> > >::iterator oter = organizedIndices.find(iter->first);
00952                                         if(iter->first != 0 && oter != organizedIndices.end())
00953                                         {
00954                                                 UDEBUG("Texture by pixels");
00955                                                 textureMesh->cloud = iter->second->cloud;
00956                                                 textureMesh->tex_polygons.push_back(iter->second->polygons);
00957                                                 int w = oter->second.second.first;
00958                                                 int h = oter->second.second.second;
00959                                                 UASSERT(w > 1 && h > 1);
00960                                                 UASSERT(textureMesh->tex_polygons.size() && textureMesh->tex_polygons[0].size());
00961                                                 textureMesh->tex_coordinates.resize(1);
00962                                                 int polygonSize = textureMesh->tex_polygons[0][0].vertices.size();
00963                                                 textureMesh->tex_coordinates[0].resize(polygonSize*textureMesh->tex_polygons[0].size());
00964                                                 for(unsigned int i=0; i<textureMesh->tex_polygons[0].size(); ++i)
00965                                                 {
00966                                                         const pcl::Vertices & vertices = textureMesh->tex_polygons[0][i];
00967                                                         UASSERT(polygonSize == (int)vertices.vertices.size());
00968                                                         for(int k=0; k<polygonSize; ++k)
00969                                                         {
00970                                                                 //uv
00971                                                                 std::map<int, int>::iterator vter = oter->second.first.find(vertices.vertices[k]);
00972                                                                 UASSERT(vter != oter->second.first.end());
00973                                                                 int originalVertex = vter->second;
00974                                                                 textureMesh->tex_coordinates[0][i*polygonSize+k] = Eigen::Vector2f(
00975                                                                                 float(originalVertex % w) / float(w),   // u
00976                                                                                 float(h - originalVertex / w) / float(h)); // v
00977                                                         }
00978                                                 }
00979                                                 pcl::TexMaterial mesh_material;
00980                                                 mesh_material.tex_d = 1.0f;
00981                                                 mesh_material.tex_Ns = 75.0f;
00982                                                 mesh_material.tex_illum = 1;
00983 
00984                                                 std::stringstream tex_name;
00985                                                 tex_name << "material_" << iter->first;
00986                                                 tex_name >> mesh_material.tex_name;
00987 
00988                                                 std::string tmpDirectory = dir.filePath("tmp_textures").toStdString();
00989                                                 mesh_material.tex_file = uFormat("%s/%s%d.png", tmpDirectory.c_str(), "texture_", iter->first);
00990                                                 if(!cv::imwrite(mesh_material.tex_file, images.at(iter->first)))
00991                                                 {
00992                                                         UERROR("Cannot save texture of image %d", iter->first);
00993                                                 }
00994                                                 else
00995                                                 {
00996                                                         UINFO("Saved temporary texture: \"%s\"", mesh_material.tex_file.c_str());
00997                                                 }
00998 
00999                                                 textureMesh->tex_materials.push_back(mesh_material);
01000                                         }
01001                                         else
01002                                         {
01003                                                 UDEBUG("Texture by projection");
01004                                                 textureMesh = util3d::createTextureMesh(
01005                                                                 iter->second,
01006                                                                 cameraPoses,
01007                                                                 cameraModels,
01008                                                                 images,
01009                                                                 dir.filePath("tmp_textures").toStdString());
01010                                         }
01011 
01012                                         textureMeshes.insert(std::make_pair(iter->first, textureMesh));
01013                                 }
01014                                 else
01015                                 {
01016                                         UWARN("No camera poses!?");
01017                                 }
01018 
01019                                 _progressDialog->appendText(tr("TextureMesh %1 created [cameras=%2] (%3/%4).").arg(iter->first).arg(cameraPoses.size()).arg(++i).arg(meshes.size()));
01020                                 _progressDialog->incrementStep();
01021                                 QApplication::processEvents();
01022                         }
01023 
01024                         if(textureMeshes.size() > 1 && _ui->checkBox_assemble->isChecked())
01025                         {
01026                                 _progressDialog->appendText(tr("Assembling %1 meshes...").arg(textureMeshes.size()));
01027                                 QApplication::processEvents();
01028                                 uSleep(100);
01029                                 QApplication::processEvents();
01030 
01031                                 pcl::TextureMesh::Ptr assembledMesh = util3d::concatenateTextureMeshes(uValuesList(textureMeshes));
01032                                 textureMeshes.clear();
01033                                 textureMeshes.insert(std::make_pair(0, assembledMesh));
01034                         }
01035 
01036                 }
01037 
01038                 return true;
01039         }
01040         return false;
01041 }
01042 
01043 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > ExportCloudsDialog::getClouds(
01044                 const std::map<int, Transform> & poses,
01045                 const QMap<int, Signature> & cachedSignatures,
01046                 const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
01047                 const ParametersMap & parameters) const
01048 {
01049         std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
01050         int i=0;
01051         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr previousCloud;
01052         pcl::IndicesPtr previousIndices;
01053         Transform previousPose;
01054         for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end(); ++iter)
01055         {
01056                 int points = 0;
01057                 int totalIndices = 0;
01058                 if(!iter->second.isNull())
01059                 {
01060                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
01061                         pcl::IndicesPtr indices(new std::vector<int>);
01062                         if(_ui->groupBox_regenerate->isChecked())
01063                         {
01064                                 if(cachedSignatures.contains(iter->first))
01065                                 {
01066                                         const Signature & s = cachedSignatures.find(iter->first).value();
01067                                         SensorData d = s.sensorData();
01068                                         cv::Mat image, depth;
01069                                         d.uncompressData(&image, &depth, 0);
01070                                         if(!image.empty() && !depth.empty())
01071                                         {
01072                                                 UASSERT(iter->first == d.id());
01073                                                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
01074                                                 cloudWithoutNormals = util3d::cloudRGBFromSensorData(
01075                                                                 d,
01076                                                                 _ui->spinBox_decimation->value(),
01077                                                                 _ui->doubleSpinBox_maxDepth->value(),
01078                                                                 _ui->doubleSpinBox_minDepth->value(),
01079                                                                 indices.get(),
01080                                                                 parameters);
01081 
01082                                                 // Don't voxelize if we create organized mesh
01083                                                 if(!(_ui->comboBox_pipeline->currentIndex()==0 && _ui->groupBox_meshing->isChecked()))
01084                                                 {
01085                                                         cloudWithoutNormals = util3d::voxelize(cloudWithoutNormals, indices, _ui->doubleSpinBox_voxelSize_assembled->value());
01086                                                         indices->resize(cloudWithoutNormals->size());
01087                                                         for(unsigned int i=0; i<indices->size(); ++i)
01088                                                         {
01089                                                                 indices->at(i) = i;
01090                                                         }
01091                                                 }
01092 
01093                                                 // view point
01094                                                 Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
01095                                                 if(d.cameraModels().size() && !d.cameraModels()[0].localTransform().isNull())
01096                                                 {
01097                                                         viewPoint[0] = d.cameraModels()[0].localTransform().x();
01098                                                         viewPoint[1] = d.cameraModels()[0].localTransform().y();
01099                                                         viewPoint[2] = d.cameraModels()[0].localTransform().z();
01100                                                 }
01101                                                 else if(!d.stereoCameraModel().localTransform().isNull())
01102                                                 {
01103                                                         viewPoint[0] = d.stereoCameraModel().localTransform().x();
01104                                                         viewPoint[1] = d.stereoCameraModel().localTransform().y();
01105                                                         viewPoint[2] = d.stereoCameraModel().localTransform().z();
01106                                                 }
01107 
01108                                                 pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), viewPoint);
01109                                                 pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
01110 
01111                                                 if(_ui->groupBox_subtraction->isChecked() &&
01112                                                    _ui->doubleSpinBox_subtractPointFilteringRadius->value() > 0.0)
01113                                                 {
01114                                                         pcl::IndicesPtr beforeSubtractionIndices = indices;
01115                                                         if(     cloud->size() &&
01116                                                                 previousCloud.get() != 0 &&
01117                                                                 previousIndices.get() != 0 &&
01118                                                                 previousIndices->size() &&
01119                                                                 !previousPose.isNull())
01120                                                         {
01121                                                                 rtabmap::Transform t = iter->second.inverse() * previousPose;
01122                                                                 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformedCloud = rtabmap::util3d::transformPointCloud(previousCloud, t);
01123                                                                 indices = rtabmap::util3d::subtractFiltering(
01124                                                                                 cloud,
01125                                                                                 indices,
01126                                                                                 transformedCloud,
01127                                                                                 previousIndices,
01128                                                                                 _ui->doubleSpinBox_subtractPointFilteringRadius->value(),
01129                                                                                 _ui->doubleSpinBox_subtractPointFilteringAngle->value(),
01130                                                                                 _ui->spinBox_subtractFilteringMinPts->value());
01131                                                         }
01132                                                         previousCloud = cloud;
01133                                                         previousIndices = beforeSubtractionIndices;
01134                                                         previousPose = iter->second;
01135                                                 }
01136 
01137                                         }
01138                                         else if(s.getWords3().size())
01139                                         {
01140                                                 cloud->resize(s.getWords3().size());
01141                                                 int oi=0;
01142                                                 indices->resize(cloud->size());
01143                                                 for(std::multimap<int, cv::Point3f>::const_iterator jter=s.getWords3().begin(); jter!=s.getWords3().end(); ++jter)
01144                                                 {
01145                                                         indices->at(oi) = oi;
01146                                                         (*cloud)[oi].x = jter->second.x;
01147                                                         (*cloud)[oi].y = jter->second.y;
01148                                                         (*cloud)[oi].z = jter->second.z;
01149                                                         (*cloud)[oi].r = 255;
01150                                                         (*cloud)[oi].g = 255;
01151                                                         (*cloud)[oi++].b = 255;
01152                                                 }
01153                                         }
01154                                 }
01155                                 else
01156                                 {
01157                                         UERROR("Cloud %d not found in cache!", iter->first);
01158                                 }
01159                         }
01160                         else if(uContains(cachedClouds, iter->first))
01161                         {
01162                                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
01163                                 if(!_ui->groupBox_meshing->isChecked() &&
01164                                    _ui->doubleSpinBox_voxelSize_assembled->value() > 0.0)
01165                                 {
01166                                         cloudWithoutNormals = util3d::voxelize(
01167                                                         cachedClouds.at(iter->first).first,
01168                                                         cachedClouds.at(iter->first).second,
01169                                                         _ui->doubleSpinBox_voxelSize_assembled->value());
01170 
01171                                         //generate indices for all points (they are all valid)
01172                                         indices->resize(cloudWithoutNormals->size());
01173                                         for(unsigned int i=0; i<cloudWithoutNormals->size(); ++i)
01174                                         {
01175                                                 indices->at(i) = i;
01176                                         }
01177                                 }
01178                                 else
01179                                 {
01180                                         cloudWithoutNormals = cachedClouds.at(iter->first).first;
01181                                         indices = cachedClouds.at(iter->first).second;
01182                                 }
01183 
01184                                 // view point
01185                                 Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
01186                                 if(cachedSignatures.contains(iter->first))
01187                                 {
01188                                         const Signature & s = cachedSignatures.find(iter->first).value();
01189                                         SensorData d = s.sensorData();
01190                                         if(d.cameraModels().size() && !d.cameraModels()[0].localTransform().isNull())
01191                                         {
01192                                                 viewPoint[0] = d.cameraModels()[0].localTransform().x();
01193                                                 viewPoint[1] = d.cameraModels()[0].localTransform().y();
01194                                                 viewPoint[2] = d.cameraModels()[0].localTransform().z();
01195                                         }
01196                                         else if(!d.stereoCameraModel().localTransform().isNull())
01197                                         {
01198                                                 viewPoint[0] = d.stereoCameraModel().localTransform().x();
01199                                                 viewPoint[1] = d.stereoCameraModel().localTransform().y();
01200                                                 viewPoint[2] = d.stereoCameraModel().localTransform().z();
01201                                         }
01202                                 }
01203                                 else
01204                                 {
01205                                         _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(++i).arg(poses.size()));
01206                                 }
01207 
01208                                 pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), viewPoint);
01209                                 pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
01210                         }
01211                         else
01212                         {
01213                                 _progressDialog->appendText(tr("Cached cloud %1 not found. You may want to regenerate the clouds (%2/%3).").arg(iter->first).arg(++i).arg(poses.size()));
01214                         }
01215 
01216                         if(indices->size())
01217                         {
01218                                 if(_ui->groupBox_filtering->isChecked() &&
01219                                         _ui->doubleSpinBox_filteringRadius->value() > 0.0f &&
01220                                         _ui->spinBox_filteringMinNeighbors->value() > 0)
01221                                 {
01222                                         indices = util3d::radiusFiltering(cloud, indices, _ui->doubleSpinBox_filteringRadius->value(), _ui->spinBox_filteringMinNeighbors->value());
01223                                 }
01224 
01225                                 clouds.insert(std::make_pair(iter->first, std::make_pair(cloud, indices)));
01226                                 points = cloud->size();
01227                                 totalIndices = indices->size();
01228                         }
01229                 }
01230                 else
01231                 {
01232                         UERROR("transform is null!?");
01233                 }
01234 
01235                 if(points>0)
01236                 {
01237                         if(_ui->groupBox_regenerate->isChecked())
01238                         {
01239                                 _progressDialog->appendText(tr("Generated cloud %1 with %2 points and %3 indices (%4/%5).")
01240                                                 .arg(iter->first).arg(points).arg(totalIndices).arg(++i).arg(poses.size()));
01241                         }
01242                         else
01243                         {
01244                                 _progressDialog->appendText(tr("Copied cloud %1 from cache with %2 points and %3 indices (%4/%5).")
01245                                                 .arg(iter->first).arg(points).arg(totalIndices).arg(++i).arg(poses.size()));
01246                         }
01247                 }
01248                 else
01249                 {
01250                         _progressDialog->appendText(tr("Ignored cloud %1 (%2/%3).").arg(iter->first).arg(++i).arg(poses.size()));
01251                 }
01252                 _progressDialog->incrementStep();
01253                 QApplication::processEvents();
01254         }
01255 
01256         return clouds;
01257 }
01258 
01259 
01260 void ExportCloudsDialog::saveClouds(
01261                 const QString & workingDirectory,
01262                 const std::map<int, Transform> & poses,
01263                 const std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds,
01264                 bool binaryMode)
01265 {
01266         if(clouds.size() == 1)
01267         {
01268                 QString path = QFileDialog::getSaveFileName(this, tr("Save cloud to ..."), workingDirectory+QDir::separator()+"cloud.ply", tr("Point cloud data (*.ply *.pcd)"));
01269                 if(!path.isEmpty())
01270                 {
01271                         if(clouds.begin()->second->size())
01272                         {
01273                                 _progressDialog->appendText(tr("Saving the cloud (%1 points)...").arg(clouds.begin()->second->size()));
01274 
01275                                 bool success =false;
01276                                 if(QFileInfo(path).suffix() == "pcd")
01277                                 {
01278                                         success = pcl::io::savePCDFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
01279                                 }
01280                                 else if(QFileInfo(path).suffix() == "ply")
01281                                 {
01282                                         success = pcl::io::savePLYFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
01283                                 }
01284                                 else if(QFileInfo(path).suffix() == "")
01285                                 {
01286                                         //use ply by default
01287                                         path += ".ply";
01288                                         success = pcl::io::savePLYFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
01289                                 }
01290                                 else
01291                                 {
01292                                         UERROR("Extension not recognized! (%s) Should be one of (*.ply *.pcd).", QFileInfo(path).suffix().toStdString().c_str());
01293                                 }
01294                                 if(success)
01295                                 {
01296                                         _progressDialog->incrementStep();
01297                                         _progressDialog->appendText(tr("Saving the cloud (%1 points)... done.").arg(clouds.begin()->second->size()));
01298 
01299                                         QMessageBox::information(this, tr("Save successful!"), tr("Cloud saved to \"%1\"").arg(path));
01300                                 }
01301                                 else
01302                                 {
01303                                         QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
01304                                 }
01305                         }
01306                         else
01307                         {
01308                                 QMessageBox::warning(this, tr("Save failed!"), tr("Cloud is empty..."));
01309                         }
01310                 }
01311         }
01312         else if(clouds.size())
01313         {
01314                 QString path = QFileDialog::getExistingDirectory(this, tr("Save clouds to (*.ply *.pcd)..."), workingDirectory, 0);
01315                 if(!path.isEmpty())
01316                 {
01317                         bool ok = false;
01318                         QStringList items;
01319                         items.push_back("ply");
01320                         items.push_back("pcd");
01321                         QString suffix = QInputDialog::getItem(this, tr("File format"), tr("Which format?"), items, 0, false, &ok);
01322 
01323                         if(ok)
01324                         {
01325                                 QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "cloud", &ok);
01326 
01327                                 if(ok)
01328                                 {
01329                                         for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::const_iterator iter=clouds.begin(); iter!=clouds.end(); ++iter)
01330                                         {
01331                                                 if(iter->second->size())
01332                                                 {
01333                                                         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformedCloud;
01334                                                         transformedCloud = util3d::transformPointCloud(iter->second, poses.at(iter->first));
01335 
01336                                                         QString pathFile = path+QDir::separator()+QString("%1%2.%3").arg(prefix).arg(iter->first).arg(suffix);
01337                                                         bool success =false;
01338                                                         if(suffix == "pcd")
01339                                                         {
01340                                                                 success = pcl::io::savePCDFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
01341                                                         }
01342                                                         else if(suffix == "ply")
01343                                                         {
01344                                                                 success = pcl::io::savePLYFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
01345                                                         }
01346                                                         else
01347                                                         {
01348                                                                 UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
01349                                                         }
01350                                                         if(success)
01351                                                         {
01352                                                                 _progressDialog->appendText(tr("Saved cloud %1 (%2 points) to %3.").arg(iter->first).arg(iter->second->size()).arg(pathFile));
01353                                                         }
01354                                                         else
01355                                                         {
01356                                                                 _progressDialog->appendText(tr("Failed saving cloud %1 (%2 points) to %3.").arg(iter->first).arg(iter->second->size()).arg(pathFile));
01357                                                         }
01358                                                 }
01359                                                 else
01360                                                 {
01361                                                         _progressDialog->appendText(tr("Cloud %1 is empty!").arg(iter->first));
01362                                                 }
01363                                                 _progressDialog->incrementStep();
01364                                                 QApplication::processEvents();
01365                                         }
01366                                 }
01367                         }
01368                 }
01369         }
01370 }
01371 
01372 void ExportCloudsDialog::saveMeshes(
01373                 const QString & workingDirectory,
01374                 const std::map<int, Transform> & poses,
01375                 const std::map<int, pcl::PolygonMesh::Ptr> & meshes,
01376                 bool binaryMode)
01377 {
01378         if(meshes.size() == 1)
01379         {
01380                 QString path = QFileDialog::getSaveFileName(this, tr("Save mesh to ..."), workingDirectory+QDir::separator()+"mesh.ply", tr("Mesh (*.ply)"));
01381                 if(!path.isEmpty())
01382                 {
01383                         if(meshes.begin()->second->polygons.size())
01384                         {
01385                                 _progressDialog->appendText(tr("Saving the mesh (%1 polygons)...").arg(meshes.begin()->second->polygons.size()));
01386                                 QApplication::processEvents();
01387                                 uSleep(100);
01388                                 QApplication::processEvents();
01389 
01390                                 bool success =false;
01391                                 if(QFileInfo(path).suffix() == "")
01392                                 {
01393                                         path += ".ply";
01394                                 }
01395                                 else if(QFileInfo(path).suffix() == "ply")
01396                                 {
01397                                         if(binaryMode)
01398                                         {
01399                                                 success = pcl::io::savePLYFileBinary(path.toStdString(), *meshes.begin()->second) == 0;
01400                                         }
01401                                         else
01402                                         {
01403                                                 success = pcl::io::savePLYFile(path.toStdString(), *meshes.begin()->second) == 0;
01404                                         }
01405                                 }
01406                                 else if(QFileInfo(path).suffix() == "obj")
01407                                 {
01408                                         success = pcl::io::saveOBJFile(path.toStdString(), *meshes.begin()->second) == 0;
01409                                 }
01410                                 else
01411                                 {
01412                                         UERROR("Extension not recognized! (%s) Should be (*.ply).", QFileInfo(path).suffix().toStdString().c_str());
01413                                 }
01414                                 if(success)
01415                                 {
01416                                         _progressDialog->incrementStep();
01417                                         _progressDialog->appendText(tr("Saving the mesh (%1 polygons)... done.").arg(meshes.begin()->second->polygons.size()));
01418 
01419                                         QMessageBox::information(this, tr("Save successful!"), tr("Mesh saved to \"%1\"").arg(path));
01420                                 }
01421                                 else
01422                                 {
01423                                         QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
01424                                 }
01425                         }
01426                         else
01427                         {
01428                                 QMessageBox::warning(this, tr("Save failed!"), tr("Cloud is empty..."));
01429                         }
01430                 }
01431         }
01432         else if(meshes.size())
01433         {
01434                 QString path = QFileDialog::getExistingDirectory(this, tr("Save meshes to (*.ply *.obj)..."), workingDirectory, 0);
01435                 if(!path.isEmpty())
01436                 {
01437                         bool ok = false;
01438                         QStringList items;
01439                         items.push_back("ply");
01440                         items.push_back("obj");
01441                         QString suffix = QInputDialog::getItem(this, tr("File format"), tr("Which format?"), items, 0, false, &ok);
01442 
01443                         if(ok)
01444                         {
01445                                 QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "mesh", &ok);
01446 
01447                                 if(ok)
01448                                 {
01449                                         for(std::map<int, pcl::PolygonMesh::Ptr>::const_iterator iter=meshes.begin(); iter!=meshes.end(); ++iter)
01450                                         {
01451                                                 if(iter->second->polygons.size())
01452                                                 {
01453                                                         pcl::PolygonMesh mesh;
01454                                                         mesh.polygons = iter->second->polygons;
01455                                                         bool isRGB = false;
01456                                                         for(unsigned int i=0; i<iter->second->cloud.fields.size(); ++i)
01457                                                         {
01458                                                                 if(iter->second->cloud.fields[i].name.compare("rgb") == 0)
01459                                                                 {
01460                                                                         isRGB=true;
01461                                                                         break;
01462                                                                 }
01463                                                         }
01464                                                         if(isRGB)
01465                                                         {
01466                                                                 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZRGB>);
01467                                                                 pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
01468                                                                 tmp = util3d::transformPointCloud(tmp, poses.at(iter->first));
01469                                                                 pcl::toPCLPointCloud2(*tmp, mesh.cloud);
01470                                                         }
01471                                                         else
01472                                                         {
01473                                                                 pcl::PointCloud<pcl::PointXYZ>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZ>);
01474                                                                 pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
01475                                                                 tmp = util3d::transformPointCloud(tmp, poses.at(iter->first));
01476                                                                 pcl::toPCLPointCloud2(*tmp, mesh.cloud);
01477                                                         }
01478 
01479                                                         QString pathFile = path+QDir::separator()+QString("%1%2.%3").arg(prefix).arg(iter->first).arg(suffix);
01480                                                         bool success =false;
01481                                                         if(suffix == "ply")
01482                                                         {
01483                                                                 if(binaryMode)
01484                                                                 {
01485                                                                         success = pcl::io::savePLYFileBinary(pathFile.toStdString(), mesh) == 0;
01486                                                                 }
01487                                                                 else
01488                                                                 {
01489                                                                         success = pcl::io::savePLYFile(pathFile.toStdString(), mesh) == 0;
01490                                                                 }
01491                                                         }
01492                                                         else if(suffix == "obj")
01493                                                         {
01494                                                                 success = pcl::io::saveOBJFile(pathFile.toStdString(), mesh) == 0;
01495                                                         }
01496                                                         else
01497                                                         {
01498                                                                 UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
01499                                                         }
01500                                                         if(success)
01501                                                         {
01502                                                                 _progressDialog->appendText(tr("Saved mesh %1 (%2 polygons) to %3.")
01503                                                                                 .arg(iter->first).arg(iter->second->polygons.size()).arg(pathFile));
01504                                                         }
01505                                                         else
01506                                                         {
01507                                                                 _progressDialog->appendText(tr("Failed saving mesh %1 (%2 polygons) to %3.")
01508                                                                                 .arg(iter->first).arg(iter->second->polygons.size()).arg(pathFile));
01509                                                         }
01510                                                 }
01511                                                 else
01512                                                 {
01513                                                         _progressDialog->appendText(tr("Mesh %1 is empty!").arg(iter->first));
01514                                                 }
01515                                                 _progressDialog->incrementStep();
01516                                                 QApplication::processEvents();
01517                                         }
01518                                 }
01519                         }
01520                 }
01521         }
01522 }
01523 
01524 void ExportCloudsDialog::saveTextureMeshes(
01525                 const QString & workingDirectory,
01526                 const std::map<int, Transform> & poses,
01527                 const std::map<int, pcl::TextureMesh::Ptr> & meshes)
01528 {
01529         if(meshes.size() == 1)
01530         {
01531                 QString path = QFileDialog::getSaveFileName(this, tr("Save texture mesh to ..."), workingDirectory+QDir::separator()+"mesh.obj", tr("Mesh (*.obj)"));
01532                 if(!path.isEmpty())
01533                 {
01534                         if(meshes.begin()->second->tex_materials.size())
01535                         {
01536                                 _progressDialog->appendText(tr("Saving the mesh (with %1 textures)...").arg(meshes.begin()->second->tex_materials.size()));
01537                                 QApplication::processEvents();
01538                                 uSleep(100);
01539                                 QApplication::processEvents();
01540 
01541                                 bool success =false;
01542                                 if(QFileInfo(path).suffix() == "")
01543                                 {
01544                                         path += ".obj";
01545                                 }
01546 
01547                                 pcl::TextureMesh mesh;
01548                                 mesh.tex_coordinates = meshes.begin()->second->tex_coordinates;
01549                                 mesh.tex_materials = meshes.begin()->second->tex_materials;
01550                                 removeDirRecursively(QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName());
01551                                 QDir(QFileInfo(path).absoluteDir().absolutePath()).mkdir(QFileInfo(path).baseName());
01552                                 for(unsigned int i=0;i<meshes.begin()->second->tex_materials.size(); ++i)
01553                                 {
01554                                         QFileInfo info(mesh.tex_materials[i].tex_file.c_str());
01555                                         QString fullPath = QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName()+QDir::separator()+info.fileName();
01556                                         // relative path
01557                                         mesh.tex_materials[i].tex_file=(QFileInfo(path).baseName()+QDir::separator()+info.fileName()).toStdString();
01558                                         if(!QFile::copy(meshes.begin()->second->tex_materials[i].tex_file.c_str(), fullPath))
01559                                         {
01560                                                 _progressDialog->appendText(tr("Failed copying texture \"%1\" to \"%2\".")
01561                                                                 .arg(meshes.begin()->second->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
01562                                                 _progressDialog->setAutoClose(false);
01563                                         }
01564                                 }
01565                                 mesh.tex_polygons = meshes.begin()->second->tex_polygons;
01566                                 mesh.cloud = meshes.begin()->second->cloud;
01567 
01568                                 success = pcl::io::saveOBJFile(path.toStdString(), mesh) == 0;
01569                                 if(success)
01570                                 {
01571                                         _progressDialog->incrementStep();
01572                                         _progressDialog->appendText(tr("Saving the mesh (with %1 textures)... done.").arg(mesh.tex_materials.size()));
01573 
01574                                         QMessageBox::information(this, tr("Save successful!"), tr("Mesh saved to \"%1\"").arg(path));
01575                                 }
01576                                 else
01577                                 {
01578                                         QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
01579                                 }
01580                         }
01581                         else
01582                         {
01583                                 QMessageBox::warning(this, tr("Save failed!"), tr("No textures..."));
01584                         }
01585                 }
01586         }
01587         else if(meshes.size())
01588         {
01589                 QString path = QFileDialog::getExistingDirectory(this, tr("Save texture meshes to (*.obj)..."), workingDirectory, 0);
01590                 if(!path.isEmpty())
01591                 {
01592                         bool ok = false;
01593                         QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "mesh", &ok);
01594                         QString suffix = "obj";
01595 
01596                         if(ok)
01597                         {
01598                                 for(std::map<int, pcl::TextureMesh::Ptr>::const_iterator iter=meshes.begin(); iter!=meshes.end(); ++iter)
01599                                 {
01600                                         QString currentPrefix=prefix+QString::number(iter->first);
01601                                         if(iter->second->tex_materials.size())
01602                                         {
01603                                                 pcl::TextureMesh mesh;
01604                                                 mesh.tex_coordinates = iter->second->tex_coordinates;
01605                                                 mesh.tex_materials = iter->second->tex_materials;
01606                                                 QDir(path).rmdir(currentPrefix);
01607                                                 QDir(path).mkdir(currentPrefix);
01608                                                 for(unsigned int i=0;i<iter->second->tex_materials.size(); ++i)
01609                                                 {
01610                                                         QFileInfo info(mesh.tex_materials[i].tex_file.c_str());
01611                                                         QString fullPath = path+QDir::separator()+currentPrefix+QDir::separator()+info.fileName();
01612                                                         // relative path
01613                                                         mesh.tex_materials[i].tex_file=(currentPrefix+QDir::separator()+info.fileName()).toStdString();
01614                                                         if(!QFile::copy(iter->second->tex_materials[i].tex_file.c_str(), fullPath) &&
01615                                                                         info.fileName().compare("occluded.png") != 0)
01616                                                         {
01617                                                                 _progressDialog->appendText(tr("Failed copying texture \"%1\" to \"%2\".")
01618                                                                                 .arg(iter->second->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
01619                                                                 _progressDialog->setAutoClose(false);
01620                                                         }
01621                                                 }
01622                                                 mesh.tex_polygons = iter->second->tex_polygons;
01623                                                 pcl::PointCloud<pcl::PointNormal>::Ptr tmp(new pcl::PointCloud<pcl::PointNormal>);
01624                                                 pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
01625                                                 tmp = util3d::transformPointCloud(tmp, poses.at(iter->first));
01626                                                 pcl::toPCLPointCloud2(*tmp, mesh.cloud);
01627 
01628                                                 QString pathFile = path+QDir::separator()+QString("%1.%3").arg(currentPrefix).arg(suffix);
01629                                                 bool success =false;
01630                                                 if(suffix == "obj")
01631                                                 {
01632                                                         success = pcl::io::saveOBJFile(pathFile.toStdString(), mesh) == 0;
01633                                                 }
01634                                                 else
01635                                                 {
01636                                                         UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
01637                                                 }
01638                                                 if(success)
01639                                                 {
01640                                                         _progressDialog->appendText(tr("Saved mesh %1 (%2 textures) to %3.")
01641                                                                         .arg(iter->first).arg(iter->second->tex_materials.size()-1).arg(pathFile));
01642                                                 }
01643                                                 else
01644                                                 {
01645                                                         _progressDialog->appendText(tr("Failed saving mesh %1 (%2 textures) to %3.")
01646                                                                         .arg(iter->first).arg(iter->second->tex_materials.size()-1).arg(pathFile), Qt::darkRed);
01647                                                 }
01648                                         }
01649                                         else
01650                                         {
01651                                                 _progressDialog->appendText(tr("Mesh %1 is empty!").arg(iter->first));
01652                                         }
01653                                         _progressDialog->incrementStep();
01654                                         QApplication::processEvents();
01655                                 }
01656                         }
01657                 }
01658         }
01659 }
01660 
01661 }


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:16