ExportCloudsDialog.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
29 #include "ui_exportCloudsDialog.h"
30 
36 #include "rtabmap/utilite/UStl.h"
37 #include "rtabmap/utilite/UMath.h"
38 
42 #include "rtabmap/core/util3d.h"
43 #include "rtabmap/core/util2d.h"
44 #include "rtabmap/core/Graph.h"
47 #include "rtabmap/core/DBDriver.h"
48 #include "rtabmap/core/Version.h"
49 
50 #include <pcl/conversions.h>
51 #include <pcl/io/pcd_io.h>
52 #include <pcl/io/ply_io.h>
53 #include <pcl/io/vtk_io.h>
54 #include <pcl/io/obj_io.h>
55 #include <pcl/pcl_config.h>
56 #include <pcl/surface/poisson.h>
57 #include <pcl/common/common.h>
58 
59 #include <QPushButton>
60 #include <QDir>
61 #include <QFileInfo>
62 #include <QMessageBox>
63 #include <QFileDialog>
64 #include <QInputDialog>
65 #include <QDesktopWidget>
66 
67 #ifdef RTABMAP_CPUTSDF
68 #include <cpu_tsdf/tsdf_volume_octree.h>
69 #include <cpu_tsdf/marching_cubes_tsdf_octree.h>
70 #endif
71 
72 #ifdef RTABMAP_OPENCHISEL
73 #include "chisel_conversions.h"
74 #include <open_chisel/ProjectionIntegrator.h>
75 #include <open_chisel/truncation/QuadraticTruncator.h>
76 #include <open_chisel/weighting/ConstantWeighter.h>
77 #endif
78 
79 #ifdef RTABMAP_PDAL
81 #endif
82 
83 namespace rtabmap {
84 
86  QDialog(parent),
87  _canceled(false),
88  _compensator(0),
89  _dbDriver(0),
90  _scansHaveRGB(false)
91 {
92  _ui = new Ui_ExportCloudsDialog();
93  _ui->setupUi(this);
94 
95  connect(_ui->buttonBox->button(QDialogButtonBox::RestoreDefaults), SIGNAL(clicked()), this, SLOT(restoreDefaults()));
96  QPushButton * loadSettingsButton = _ui->buttonBox->addButton("Load Settings", QDialogButtonBox::ActionRole);
97  QPushButton * saveSettingsButton = _ui->buttonBox->addButton("Save Settings", QDialogButtonBox::ActionRole);
98  connect(loadSettingsButton, SIGNAL(clicked()), this, SLOT(loadSettings()));
99  connect(saveSettingsButton, SIGNAL(clicked()), this, SLOT(saveSettings()));
100 
101  restoreDefaults();
102  _ui->comboBox_upsamplingMethod->setItemData(1, 0, Qt::UserRole - 1); // disable DISTINCT_CLOUD
103 
104  connect(_ui->checkBox_fromDepth, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
105  connect(_ui->checkBox_fromDepth, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
106  connect(_ui->checkBox_binary, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
107  connect(_ui->spinBox_normalKSearch, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
108  connect(_ui->doubleSpinBox_normalRadiusSearch, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
109  connect(_ui->doubleSpinBox_groundNormalsUp, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
110  connect(_ui->comboBox_pipeline, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
111  connect(_ui->comboBox_pipeline, SIGNAL(currentIndexChanged(int)), this, SLOT(updateReconstructionFlavor()));
112  connect(_ui->comboBox_meshingApproach, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
113  connect(_ui->comboBox_meshingApproach, SIGNAL(currentIndexChanged(int)), this, SLOT(updateReconstructionFlavor()));
114 
115  connect(_ui->checkBox_nodes_filtering, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
116  connect(_ui->checkBox_nodes_filtering, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
117  connect(_ui->doubleSpinBox_nodes_filtering_xmin, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
118  connect(_ui->doubleSpinBox_nodes_filtering_xmax, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
119  connect(_ui->doubleSpinBox_nodes_filtering_ymin, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
120  connect(_ui->doubleSpinBox_nodes_filtering_ymax, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
121  connect(_ui->doubleSpinBox_nodes_filtering_zmin, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
122  connect(_ui->doubleSpinBox_nodes_filtering_zmax, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
123 
124  connect(_ui->checkBox_regenerate, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
125  connect(_ui->checkBox_regenerate, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
126  connect(_ui->spinBox_decimation, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
127  connect(_ui->doubleSpinBox_maxDepth, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
128  connect(_ui->doubleSpinBox_minDepth, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
129  connect(_ui->doubleSpinBox_ceilingHeight, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
130  connect(_ui->doubleSpinBox_floorHeight, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
131  connect(_ui->doubleSpinBox_footprintWidth, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
132  connect(_ui->doubleSpinBox_footprintLength, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
133  connect(_ui->doubleSpinBox_footprintHeight, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
134  connect(_ui->spinBox_decimation_scan, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
135  connect(_ui->doubleSpinBox_rangeMin, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
136  connect(_ui->doubleSpinBox_rangeMax, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
137  connect(_ui->spinBox_fillDepthHoles, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
138  connect(_ui->spinBox_fillDepthHolesError, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
139  connect(_ui->lineEdit_roiRatios, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
140  connect(_ui->lineEdit_distortionModel, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
141  connect(_ui->toolButton_distortionModel, SIGNAL(clicked()), this, SLOT(selectDistortionModel()));
142 
143  connect(_ui->checkBox_bilateral, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
144  connect(_ui->checkBox_bilateral, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
145  connect(_ui->doubleSpinBox_bilateral_sigmaS, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
146  connect(_ui->doubleSpinBox_bilateral_sigmaR, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
147 
148  connect(_ui->checkBox_filtering, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
149  connect(_ui->checkBox_filtering, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
150  connect(_ui->doubleSpinBox_filteringRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
151  connect(_ui->spinBox_filteringMinNeighbors, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
152 
153  connect(_ui->checkBox_assemble, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
154  connect(_ui->checkBox_assemble, SIGNAL(clicked(bool)), this, SLOT(updateReconstructionFlavor()));
155  connect(_ui->doubleSpinBox_voxelSize_assembled, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
156  connect(_ui->spinBox_randomSamples_assembled, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
157  connect(_ui->comboBox_frame, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
158  connect(_ui->comboBox_frame, SIGNAL(currentIndexChanged(int)), this, SLOT(updateReconstructionFlavor()));
159 
160  connect(_ui->checkBox_subtraction, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
161  connect(_ui->checkBox_subtraction, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
162  connect(_ui->doubleSpinBox_subtractPointFilteringRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
163  connect(_ui->doubleSpinBox_subtractPointFilteringAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
164  connect(_ui->spinBox_subtractFilteringMinPts, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
165 
166  connect(_ui->checkBox_smoothing, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
167  connect(_ui->checkBox_smoothing, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
168  connect(_ui->doubleSpinBox_mlsRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
169  connect(_ui->spinBox_polygonialOrder, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
170  connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
171  connect(_ui->doubleSpinBox_sampleStep, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
172  connect(_ui->spinBox_randomPoints, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
173  connect(_ui->doubleSpinBox_dilationVoxelSize, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
174  connect(_ui->spinBox_dilationSteps, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
175  connect(_ui->doubleSpinBox_mls_outputVoxelSize, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
176  _ui->stackedWidget_upsampling->setCurrentIndex(_ui->comboBox_upsamplingMethod->currentIndex());
177  connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_upsampling, SLOT(setCurrentIndex(int)));
178  connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), this, SLOT(updateMLSGrpVisibility()));
179 
180  connect(_ui->checkBox_gainCompensation, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
181  connect(_ui->checkBox_gainCompensation, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
182  connect(_ui->doubleSpinBox_gainRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
183  connect(_ui->doubleSpinBox_gainOverlap, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
184  connect(_ui->doubleSpinBox_gainBeta, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
185  connect(_ui->checkBox_gainRGB, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
186  connect(_ui->checkBox_gainFull, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
187  connect(_ui->spinBox_textureBrightnessContrastRatioLow, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
188  connect(_ui->spinBox_textureBrightnessContrastRatioHigh, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
189  connect(_ui->checkBox_exposureFusion, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
190  connect(_ui->checkBox_blending, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
191  connect(_ui->comboBox_blendingDecimation, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
192 
193  connect(_ui->checkBox_cameraProjection, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
194  connect(_ui->checkBox_cameraProjection, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
195  connect(_ui->lineEdit_camProjRoiRatios, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
196  connect(_ui->toolButton_camProjMaskFilePath, SIGNAL(clicked()), this, SLOT(selectCamProjMask()));
197  connect(_ui->lineEdit_camProjMaskFilePath, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
198  connect(_ui->spinBox_camProjDecimation, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
199  connect(_ui->doubleSpinBox_camProjMaxDistance, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
200  connect(_ui->doubleSpinBox_camProjMaxAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
201  connect(_ui->checkBox_camProjDistanceToCamPolicy, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
202  connect(_ui->checkBox_camProjKeepPointsNotSeenByCameras, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
203  connect(_ui->checkBox_camProjRecolorPoints, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
204  connect(_ui->comboBox_camProjExportCamera, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
205 #ifndef RTABMAP_PDAL
206  _ui->comboBox_camProjExportCamera->setEnabled(false);
207  _ui->label_camProjExportCamera->setEnabled(false);
208  _ui->label_camProjExportCamera->setText(_ui->label_camProjExportCamera->text() + " (PDAL dependency required)");
209 #endif
210 
211  connect(_ui->checkBox_meshing, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
212  connect(_ui->checkBox_meshing, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
213  connect(_ui->doubleSpinBox_gp3Radius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
214  connect(_ui->doubleSpinBox_gp3Mu, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
215  connect(_ui->doubleSpinBox_meshDecimationFactor, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
216  connect(_ui->doubleSpinBox_meshDecimationFactor, SIGNAL(valueChanged(double)), this, SLOT(updateReconstructionFlavor()));
217  connect(_ui->spinBox_meshMaxPolygons, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
218  connect(_ui->spinBox_meshMaxPolygons, SIGNAL(valueChanged(int)), this, SLOT(updateReconstructionFlavor()));
219  connect(_ui->doubleSpinBox_transferColorRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
220  connect(_ui->checkBox_cleanMesh, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
221  connect(_ui->spinBox_mesh_minClusterSize, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
222  connect(_ui->checkBox_textureMapping, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
223  connect(_ui->checkBox_textureMapping, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
224  connect(_ui->comboBox_meshingTextureFormat, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
225  connect(_ui->comboBox_meshingTextureSize, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
226  connect(_ui->spinBox_mesh_maxTextures, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
227  connect(_ui->doubleSpinBox_meshingTextureMaxDistance, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
228  connect(_ui->doubleSpinBox_meshingTextureMaxDepthError, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
229  connect(_ui->doubleSpinBox_meshingTextureMaxAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
230  connect(_ui->spinBox_mesh_minTextureClusterSize, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
231  connect(_ui->lineEdit_meshingTextureRoiRatios, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
232  connect(_ui->checkBox_cameraFilter, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
233  connect(_ui->checkBox_cameraFilter, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
234  connect(_ui->doubleSpinBox_cameraFilterRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
235  connect(_ui->doubleSpinBox_cameraFilterAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
236  connect(_ui->doubleSpinBox_cameraFilterVel, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
237  connect(_ui->doubleSpinBox_cameraFilterVelRad, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
238  connect(_ui->doubleSpinBox_laplacianVariance, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
239  connect(_ui->checkBox_multiband, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
240  connect(_ui->checkBox_multiband, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
241  connect(_ui->spinBox_multiband_downscale, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
242  connect(_ui->lineEdit_multiband_nbcontrib, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
243  connect(_ui->comboBox_multiband_unwrap, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
244  connect(_ui->checkBox_multiband_fillholes, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
245  connect(_ui->spinBox_multiband_padding, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
246  connect(_ui->doubleSpinBox_multiband_bestscore, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
247  connect(_ui->doubleSpinBox_multiband_angle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
248  connect(_ui->checkBox_multiband_forcevisible, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
249 
250  connect(_ui->checkBox_poisson_outputPolygons, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
251  connect(_ui->checkBox_poisson_manifold, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
252  connect(_ui->spinBox_poisson_depth, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
253  connect(_ui->doubleSpinBox_poisson_targetPolygonSize, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
254  connect(_ui->spinBox_poisson_iso, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
255  connect(_ui->spinBox_poisson_solver, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
256  connect(_ui->spinBox_poisson_minDepth, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
257  connect(_ui->doubleSpinBox_poisson_samples, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
258  connect(_ui->doubleSpinBox_poisson_pointWeight, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
259  connect(_ui->doubleSpinBox_poisson_scale, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
260 
261  connect(_ui->doubleSpinBox_cputsdf_size, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
262  connect(_ui->doubleSpinBox_cputsdf_resolution, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
263  connect(_ui->doubleSpinBox_cputsdf_tuncPos, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
264  connect(_ui->doubleSpinBox_cputsdf_tuncNeg, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
265  connect(_ui->doubleSpinBox_cputsdf_minWeight, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
266  connect(_ui->doubleSpinBox_cputsdf_flattenRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
267  connect(_ui->spinBox_cputsdf_randomSplit, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
268 
269  connect(_ui->checkBox_openchisel_mergeVertices, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
270  connect(_ui->spinBox_openchisel_chunk_size_x, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
271  connect(_ui->spinBox_openchisel_chunk_size_y, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
272  connect(_ui->spinBox_openchisel_chunk_size_z, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
273  connect(_ui->doubleSpinBox_openchisel_truncation_constant, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
274  connect(_ui->doubleSpinBox_openchisel_truncation_linear, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
275  connect(_ui->doubleSpinBox_openchisel_truncation_quadratic, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
276  connect(_ui->doubleSpinBox_openchisel_truncation_scale, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
277  connect(_ui->spinBox_openchisel_integration_weight, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
278  connect(_ui->checkBox_openchisel_use_voxel_carving, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
279  connect(_ui->doubleSpinBox_openchisel_carving_dist_m, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
280  connect(_ui->doubleSpinBox_openchisel_near_plane_dist, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
281  connect(_ui->doubleSpinBox_openchisel_far_plane_dist, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
282 
283 
284  _progressDialog = new ProgressDialog(this);
285  _progressDialog->setVisible(false);
286  _progressDialog->setAutoClose(true, 2);
287  _progressDialog->setMinimumWidth(600);
289  connect(_progressDialog, SIGNAL(canceled()), this, SLOT(cancel()));
290 
291 #ifdef DISABLE_VTK
292  _ui->doubleSpinBox_meshDecimationFactor->setEnabled(false);
293  _ui->spinBox_meshMaxPolygons->setEnabled(false);
294  _ui->label_meshDecimation->setEnabled(false);
295  _ui->label_meshMaxPolygons->setEnabled(false);
296 #endif
297 
298 #if CV_MAJOR_VERSION < 3
299  _ui->checkBox_exposureFusion->setEnabled(false);
300  _ui->checkBox_exposureFusion->setChecked(false);
301  _ui->label_exposureFusion->setEnabled(false);
302 #endif
303 }
304 
306 {
307  delete _ui;
308  delete _compensator;
309 }
310 
312 {
313  _ui->groupBox->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 0);
314  _ui->groupBox_2->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 1);
315  _ui->groupBox_3->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 2);
316  _ui->groupBox_4->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 3);
317  _ui->groupBox_5->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 4);
318 }
319 
321 {
322  _canceled = true;
323  _progressDialog->appendText(tr("Canceled!"));
324 }
325 
327 {
328  if(enabled)
329  {
330  _ui->checkBox_assemble->setChecked(true);
331  _ui->checkBox_assemble->setEnabled(false);
332  }
333  else
334  {
335  _ui->checkBox_assemble->setEnabled(true);
336  }
337 }
338 
340 {
342 }
343 
344 void ExportCloudsDialog::saveSettings(QSettings & settings, const QString & group) const
345 {
346  if(!group.isEmpty())
347  {
348  settings.beginGroup(group);
349  }
350  settings.setValue("pipeline", _ui->comboBox_pipeline->currentIndex());
351  settings.setValue("from_depth", _ui->checkBox_fromDepth->isChecked());
352  settings.setValue("binary", _ui->checkBox_binary->isChecked());
353  settings.setValue("normals_k", _ui->spinBox_normalKSearch->value());
354  settings.setValue("normals_radius", _ui->doubleSpinBox_normalRadiusSearch->value());
355  settings.setValue("normals_ground_normals_up", _ui->doubleSpinBox_groundNormalsUp->value());
356  settings.setValue("intensity_colormap", _ui->comboBox_intensityColormap->currentIndex());
357 
358  settings.setValue("nodes_filtering", _ui->checkBox_nodes_filtering->isChecked());
359  settings.setValue("nodes_filtering_xmin", _ui->doubleSpinBox_nodes_filtering_xmin->value());
360  settings.setValue("nodes_filtering_xmax", _ui->doubleSpinBox_nodes_filtering_xmax->value());
361  settings.setValue("nodes_filtering_ymin", _ui->doubleSpinBox_nodes_filtering_ymin->value());
362  settings.setValue("nodes_filtering_ymax", _ui->doubleSpinBox_nodes_filtering_ymax->value());
363  settings.setValue("nodes_filtering_zmin", _ui->doubleSpinBox_nodes_filtering_zmin->value());
364  settings.setValue("nodes_filtering_zmax", _ui->doubleSpinBox_nodes_filtering_zmax->value());
365 
366  settings.setValue("regenerate", _ui->checkBox_regenerate->isChecked());
367  settings.setValue("regenerate_decimation", _ui->spinBox_decimation->value());
368  settings.setValue("regenerate_max_depth", _ui->doubleSpinBox_maxDepth->value());
369  settings.setValue("regenerate_min_depth", _ui->doubleSpinBox_minDepth->value());
370  settings.setValue("regenerate_ceiling", _ui->doubleSpinBox_ceilingHeight->value());
371  settings.setValue("regenerate_floor", _ui->doubleSpinBox_floorHeight->value());
372  settings.setValue("regenerate_footprint_height", _ui->doubleSpinBox_footprintHeight->value());
373  settings.setValue("regenerate_footprint_width", _ui->doubleSpinBox_footprintWidth->value());
374  settings.setValue("regenerate_footprint_length", _ui->doubleSpinBox_footprintLength->value());
375  settings.setValue("regenerate_scan_decimation", _ui->spinBox_decimation_scan->value());
376  settings.setValue("regenerate_scan_max_range", _ui->doubleSpinBox_rangeMax->value());
377  settings.setValue("regenerate_scan_min_range", _ui->doubleSpinBox_rangeMin->value());
378  settings.setValue("regenerate_fill_size", _ui->spinBox_fillDepthHoles->value());
379  settings.setValue("regenerate_fill_error", _ui->spinBox_fillDepthHolesError->value());
380  settings.setValue("regenerate_roi", _ui->lineEdit_roiRatios->text());
381  settings.setValue("regenerate_distortion_model", _ui->lineEdit_distortionModel->text());
382 
383  settings.setValue("bilateral", _ui->checkBox_bilateral->isChecked());
384  settings.setValue("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value());
385  settings.setValue("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value());
386 
387  settings.setValue("filtering", _ui->checkBox_filtering->isChecked());
388  settings.setValue("filtering_radius", _ui->doubleSpinBox_filteringRadius->value());
389  settings.setValue("filtering_min_neighbors", _ui->spinBox_filteringMinNeighbors->value());
390 
391  settings.setValue("assemble", _ui->checkBox_assemble->isChecked());
392  settings.setValue("assemble_voxel",_ui->doubleSpinBox_voxelSize_assembled->value());
393  settings.setValue("assemble_samples",_ui->spinBox_randomSamples_assembled->value());
394  settings.setValue("frame",_ui->comboBox_frame->currentIndex());
395 
396  settings.setValue("subtract",_ui->checkBox_subtraction->isChecked());
397  settings.setValue("subtract_point_radius",_ui->doubleSpinBox_subtractPointFilteringRadius->value());
398  settings.setValue("subtract_point_angle",_ui->doubleSpinBox_subtractPointFilteringAngle->value());
399  settings.setValue("subtract_min_neighbors",_ui->spinBox_subtractFilteringMinPts->value());
400 
401  settings.setValue("mls", _ui->checkBox_smoothing->isChecked());
402  settings.setValue("mls_radius", _ui->doubleSpinBox_mlsRadius->value());
403  settings.setValue("mls_polygonial_order", _ui->spinBox_polygonialOrder->value());
404  settings.setValue("mls_upsampling_method", _ui->comboBox_upsamplingMethod->currentIndex());
405  settings.setValue("mls_upsampling_radius", _ui->doubleSpinBox_sampleRadius->value());
406  settings.setValue("mls_upsampling_step", _ui->doubleSpinBox_sampleStep->value());
407  settings.setValue("mls_point_density", _ui->spinBox_randomPoints->value());
408  settings.setValue("mls_dilation_voxel_size", _ui->doubleSpinBox_dilationVoxelSize->value());
409  settings.setValue("mls_dilation_iterations", _ui->spinBox_dilationSteps->value());
410  settings.setValue("mls_output_voxel_size", _ui->doubleSpinBox_mls_outputVoxelSize->value());
411 
412  settings.setValue("gain", _ui->checkBox_gainCompensation->isChecked());
413  settings.setValue("gain_radius", _ui->doubleSpinBox_gainRadius->value());
414  settings.setValue("gain_overlap", _ui->doubleSpinBox_gainOverlap->value());
415  settings.setValue("gain_beta", _ui->doubleSpinBox_gainBeta->value());
416  settings.setValue("gain_rgb", _ui->checkBox_gainRGB->isChecked());
417  settings.setValue("gain_full", _ui->checkBox_gainFull->isChecked());
418 
419  settings.setValue("cam_proj", _ui->checkBox_cameraProjection->isChecked());
420  settings.setValue("cam_proj_roi_ratios", _ui->lineEdit_camProjRoiRatios->text());
421  settings.setValue("cam_proj_mask", _ui->lineEdit_camProjMaskFilePath->text());
422  settings.setValue("cam_proj_decimation", _ui->spinBox_camProjDecimation->value());
423  settings.setValue("cam_proj_max_distance", _ui->doubleSpinBox_camProjMaxDistance->value());
424  settings.setValue("cam_proj_max_angle", _ui->doubleSpinBox_camProjMaxAngle->value());
425  settings.setValue("cam_proj_distance_policy", _ui->checkBox_camProjDistanceToCamPolicy->isChecked());
426  settings.setValue("cam_proj_keep_points", _ui->checkBox_camProjKeepPointsNotSeenByCameras->isChecked());
427  settings.setValue("cam_proj_recolor_points", _ui->checkBox_camProjRecolorPoints->isChecked());
428  settings.setValue("cam_proj_export_format", _ui->comboBox_camProjExportCamera->currentIndex());
429 
430  settings.setValue("mesh", _ui->checkBox_meshing->isChecked());
431  settings.setValue("mesh_radius", _ui->doubleSpinBox_gp3Radius->value());
432  settings.setValue("mesh_mu", _ui->doubleSpinBox_gp3Mu->value());
433  settings.setValue("mesh_decimation_factor", _ui->doubleSpinBox_meshDecimationFactor->value());
434  settings.setValue("mesh_max_polygons", _ui->spinBox_meshMaxPolygons->value());
435  settings.setValue("mesh_color_radius", _ui->doubleSpinBox_transferColorRadius->value());
436  settings.setValue("mesh_clean", _ui->checkBox_cleanMesh->isChecked());
437  settings.setValue("mesh_min_cluster_size", _ui->spinBox_mesh_minClusterSize->value());
438 
439  settings.setValue("mesh_dense_strategy", _ui->comboBox_meshingApproach->currentIndex());
440 
441  settings.setValue("mesh_texture", _ui->checkBox_textureMapping->isChecked());
442  settings.setValue("mesh_textureFormat", _ui->comboBox_meshingTextureFormat->currentIndex());
443  settings.setValue("mesh_textureSize", _ui->comboBox_meshingTextureSize->currentIndex());
444  settings.setValue("mesh_textureMaxCount", _ui->spinBox_mesh_maxTextures->value());
445  settings.setValue("mesh_textureMaxDistance", _ui->doubleSpinBox_meshingTextureMaxDistance->value());
446  settings.setValue("mesh_textureMaxDepthError", _ui->doubleSpinBox_meshingTextureMaxDepthError->value());
447  settings.setValue("mesh_textureMaxAngle", _ui->doubleSpinBox_meshingTextureMaxAngle->value());
448  settings.setValue("mesh_textureMinCluster", _ui->spinBox_mesh_minTextureClusterSize->value());
449  settings.setValue("mesh_textureRoiRatios", _ui->lineEdit_meshingTextureRoiRatios->text());
450  settings.setValue("mesh_textureDistanceToCamPolicy", _ui->checkBox_distanceToCamPolicy->isChecked());
451  settings.setValue("mesh_textureCameraFiltering", _ui->checkBox_cameraFilter->isChecked());
452  settings.setValue("mesh_textureCameraFilteringRadius", _ui->doubleSpinBox_cameraFilterRadius->value());
453  settings.setValue("mesh_textureCameraFilteringAngle", _ui->doubleSpinBox_cameraFilterAngle->value());
454  settings.setValue("mesh_textureCameraFilteringVel", _ui->doubleSpinBox_cameraFilterVel->value());
455  settings.setValue("mesh_textureCameraFilteringVelRad", _ui->doubleSpinBox_cameraFilterVelRad->value());
456  settings.setValue("mesh_textureCameraFilteringLaplacian", _ui->doubleSpinBox_laplacianVariance->value());
457  settings.setValue("mesh_textureBrightnessConstrastRatioLow", _ui->spinBox_textureBrightnessContrastRatioLow->value());
458  settings.setValue("mesh_textureBrightnessConstrastRatioHigh", _ui->spinBox_textureBrightnessContrastRatioHigh->value());
459  settings.setValue("mesh_textureExposureFusion", _ui->checkBox_exposureFusion->isChecked());
460  settings.setValue("mesh_textureBlending", _ui->checkBox_blending->isChecked());
461  settings.setValue("mesh_textureBlendingDecimation", _ui->comboBox_blendingDecimation->currentIndex());
462  settings.setValue("mesh_textureMultiband", _ui->checkBox_multiband->isChecked());
463  settings.setValue("mesh_textureMultibandDownScale", _ui->spinBox_multiband_downscale->value());
464  settings.setValue("mesh_textureMultibandNbContrib", _ui->lineEdit_multiband_nbcontrib->text());
465  settings.setValue("mesh_textureMultibandUnwrap", _ui->comboBox_multiband_unwrap->currentIndex());
466  settings.setValue("mesh_textureMultibandFillHoles", _ui->checkBox_multiband_fillholes->isChecked());
467  settings.setValue("mesh_textureMultibandPadding", _ui->spinBox_multiband_padding->value());
468  settings.setValue("mesh_textureMultibandBestScoreThr", _ui->doubleSpinBox_multiband_bestscore->value());
469  settings.setValue("mesh_textureMultibandAngleHardThr", _ui->doubleSpinBox_multiband_angle->value());
470  settings.setValue("mesh_textureMultibandForceVisible", _ui->checkBox_multiband_forcevisible->isChecked());
471 
472 
473  settings.setValue("mesh_angle_tolerance", _ui->doubleSpinBox_mesh_angleTolerance->value());
474  settings.setValue("mesh_quad", _ui->checkBox_mesh_quad->isChecked());
475  settings.setValue("mesh_triangle_size", _ui->spinBox_mesh_triangleSize->value());
476 
477  settings.setValue("poisson_outputPolygons", _ui->checkBox_poisson_outputPolygons->isChecked());
478  settings.setValue("poisson_manifold", _ui->checkBox_poisson_manifold->isChecked());
479  settings.setValue("poisson_depth", _ui->spinBox_poisson_depth->value());
480  settings.setValue("poisson_polygon_size", _ui->doubleSpinBox_poisson_targetPolygonSize->value());
481  settings.setValue("poisson_iso", _ui->spinBox_poisson_iso->value());
482  settings.setValue("poisson_solver", _ui->spinBox_poisson_solver->value());
483  settings.setValue("poisson_minDepth", _ui->spinBox_poisson_minDepth->value());
484  settings.setValue("poisson_samples", _ui->doubleSpinBox_poisson_samples->value());
485  settings.setValue("poisson_pointWeight", _ui->doubleSpinBox_poisson_pointWeight->value());
486  settings.setValue("poisson_scale", _ui->doubleSpinBox_poisson_scale->value());
487 
488  settings.setValue("cputsdf_size", _ui->doubleSpinBox_cputsdf_size->value());
489  settings.setValue("cputsdf_resolution", _ui->doubleSpinBox_cputsdf_resolution->value());
490  settings.setValue("cputsdf_truncPos", _ui->doubleSpinBox_cputsdf_tuncPos->value());
491  settings.setValue("cputsdf_truncNeg", _ui->doubleSpinBox_cputsdf_tuncNeg->value());
492  settings.setValue("cputsdf_minWeight", _ui->doubleSpinBox_cputsdf_minWeight->value());
493  settings.setValue("cputsdf_flattenRadius", _ui->doubleSpinBox_cputsdf_flattenRadius->value());
494  settings.setValue("cputsdf_randomSplit", _ui->spinBox_cputsdf_randomSplit->value());
495 
496  settings.setValue("openchisel_merge_vertices", _ui->checkBox_openchisel_mergeVertices->isChecked());
497  settings.setValue("openchisel_chunk_size_x", _ui->spinBox_openchisel_chunk_size_x->value());
498  settings.setValue("openchisel_chunk_size_y", _ui->spinBox_openchisel_chunk_size_y->value());
499  settings.setValue("openchisel_chunk_size_z", _ui->spinBox_openchisel_chunk_size_z->value());
500  settings.setValue("openchisel_truncation_constant", _ui->doubleSpinBox_openchisel_truncation_constant->value());
501  settings.setValue("openchisel_truncation_linear", _ui->doubleSpinBox_openchisel_truncation_linear->value());
502  settings.setValue("openchisel_truncation_quadratic", _ui->doubleSpinBox_openchisel_truncation_quadratic->value());
503  settings.setValue("openchisel_truncation_scale", _ui->doubleSpinBox_openchisel_truncation_scale->value());
504  settings.setValue("openchisel_integration_weight", _ui->spinBox_openchisel_integration_weight->value());
505  settings.setValue("openchisel_use_voxel_carving", _ui->checkBox_openchisel_use_voxel_carving->isChecked());
506  settings.setValue("openchisel_carving_dist_m", _ui->doubleSpinBox_openchisel_carving_dist_m->value());
507  settings.setValue("openchisel_near_plane_dist", _ui->doubleSpinBox_openchisel_near_plane_dist->value());
508  settings.setValue("openchisel_far_plane_dist", _ui->doubleSpinBox_openchisel_far_plane_dist->value());
509 
510  if(!group.isEmpty())
511  {
512  settings.endGroup();
513  }
514 }
515 
516 void ExportCloudsDialog::loadSettings(QSettings & settings, const QString & group)
517 {
518  if(!group.isEmpty())
519  {
520  settings.beginGroup(group);
521  }
522 
523  _ui->comboBox_pipeline->setCurrentIndex(settings.value("pipeline", _ui->comboBox_pipeline->currentIndex()).toInt());
524  _ui->checkBox_fromDepth->setChecked(settings.value("from_depth", _ui->checkBox_fromDepth->isChecked()).toBool());
525  _ui->checkBox_binary->setChecked(settings.value("binary", _ui->checkBox_binary->isChecked()).toBool());
526  _ui->spinBox_normalKSearch->setValue(settings.value("normals_k", _ui->spinBox_normalKSearch->value()).toInt());
527  _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value("normals_radius", _ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
528  _ui->doubleSpinBox_groundNormalsUp->setValue(settings.value("normals_ground_normals_up", _ui->doubleSpinBox_groundNormalsUp->value()).toDouble());
529  _ui->comboBox_intensityColormap->setCurrentIndex(settings.value("intensity_colormap", _ui->comboBox_intensityColormap->currentIndex()).toInt());
530 
531  _ui->checkBox_nodes_filtering->setChecked(settings.value("nodes_filtering", _ui->checkBox_nodes_filtering->isChecked()).toBool());
532  _ui->doubleSpinBox_nodes_filtering_xmin->setValue(settings.value("nodes_filtering_xmin", _ui->doubleSpinBox_nodes_filtering_xmin->value()).toInt());
533  _ui->doubleSpinBox_nodes_filtering_xmax->setValue(settings.value("nodes_filtering_xmax", _ui->doubleSpinBox_nodes_filtering_xmax->value()).toInt());
534  _ui->doubleSpinBox_nodes_filtering_ymin->setValue(settings.value("nodes_filtering_ymin", _ui->doubleSpinBox_nodes_filtering_ymin->value()).toInt());
535  _ui->doubleSpinBox_nodes_filtering_ymax->setValue(settings.value("nodes_filtering_ymax", _ui->doubleSpinBox_nodes_filtering_ymax->value()).toInt());
536  _ui->doubleSpinBox_nodes_filtering_zmin->setValue(settings.value("nodes_filtering_zmin", _ui->doubleSpinBox_nodes_filtering_zmin->value()).toInt());
537  _ui->doubleSpinBox_nodes_filtering_zmax->setValue(settings.value("nodes_filtering_zmax", _ui->doubleSpinBox_nodes_filtering_zmax->value()).toInt());
538 
539  _ui->checkBox_regenerate->setChecked(settings.value("regenerate", _ui->checkBox_regenerate->isChecked()).toBool());
540  _ui->spinBox_decimation->setValue(settings.value("regenerate_decimation", _ui->spinBox_decimation->value()).toInt());
541  _ui->doubleSpinBox_maxDepth->setValue(settings.value("regenerate_max_depth", _ui->doubleSpinBox_maxDepth->value()).toDouble());
542  _ui->doubleSpinBox_minDepth->setValue(settings.value("regenerate_min_depth", _ui->doubleSpinBox_minDepth->value()).toDouble());
543  _ui->doubleSpinBox_ceilingHeight->setValue(settings.value("regenerate_ceiling", _ui->doubleSpinBox_ceilingHeight->value()).toDouble());
544  _ui->doubleSpinBox_floorHeight->setValue(settings.value("regenerate_floor", _ui->doubleSpinBox_floorHeight->value()).toDouble());
545  _ui->doubleSpinBox_footprintHeight->setValue(settings.value("regenerate_footprint_height", _ui->doubleSpinBox_footprintHeight->value()).toDouble());
546  _ui->doubleSpinBox_footprintWidth->setValue(settings.value("regenerate_footprint_width", _ui->doubleSpinBox_footprintWidth->value()).toDouble());
547  _ui->doubleSpinBox_footprintLength->setValue(settings.value("regenerate_footprint_length", _ui->doubleSpinBox_footprintLength->value()).toDouble());
548  _ui->spinBox_decimation_scan->setValue(settings.value("regenerate_scan_decimation", _ui->spinBox_decimation_scan->value()).toInt());
549  _ui->doubleSpinBox_rangeMax->setValue(settings.value("regenerate_scan_max_range", _ui->doubleSpinBox_rangeMax->value()).toDouble());
550  _ui->doubleSpinBox_rangeMin->setValue(settings.value("regenerate_scan_min_range", _ui->doubleSpinBox_rangeMin->value()).toDouble());
551  _ui->spinBox_fillDepthHoles->setValue(settings.value("regenerate_fill_size", _ui->spinBox_fillDepthHoles->value()).toInt());
552  _ui->spinBox_fillDepthHolesError->setValue(settings.value("regenerate_fill_error", _ui->spinBox_fillDepthHolesError->value()).toInt());
553  _ui->lineEdit_roiRatios->setText(settings.value("regenerate_roi", _ui->lineEdit_roiRatios->text()).toString());
554  _ui->lineEdit_distortionModel->setText(settings.value("regenerate_distortion_model", _ui->lineEdit_distortionModel->text()).toString());
555 
556  _ui->checkBox_bilateral->setChecked(settings.value("bilateral", _ui->checkBox_bilateral->isChecked()).toBool());
557  _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
558  _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
559 
560  _ui->checkBox_filtering->setChecked(settings.value("filtering", _ui->checkBox_filtering->isChecked()).toBool());
561  _ui->doubleSpinBox_filteringRadius->setValue(settings.value("filtering_radius", _ui->doubleSpinBox_filteringRadius->value()).toDouble());
562  _ui->spinBox_filteringMinNeighbors->setValue(settings.value("filtering_min_neighbors", _ui->spinBox_filteringMinNeighbors->value()).toInt());
563 
564  if(_ui->checkBox_assemble->isEnabled())
565  {
566  _ui->checkBox_assemble->setChecked(settings.value("assemble", _ui->checkBox_assemble->isChecked()).toBool());
567  }
568  _ui->doubleSpinBox_voxelSize_assembled->setValue(settings.value("assemble_voxel", _ui->doubleSpinBox_voxelSize_assembled->value()).toDouble());
569  _ui->spinBox_randomSamples_assembled->setValue(settings.value("assemble_samples", _ui->spinBox_randomSamples_assembled->value()).toInt());
570  _ui->comboBox_frame->setCurrentIndex(settings.value("frame", _ui->comboBox_frame->currentIndex()).toInt());
571 
572  _ui->checkBox_subtraction->setChecked(settings.value("subtract",_ui->checkBox_subtraction->isChecked()).toBool());
573  _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(settings.value("subtract_point_radius",_ui->doubleSpinBox_subtractPointFilteringRadius->value()).toDouble());
574  _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(settings.value("subtract_point_angle",_ui->doubleSpinBox_subtractPointFilteringAngle->value()).toDouble());
575  _ui->spinBox_subtractFilteringMinPts->setValue(settings.value("subtract_min_neighbors",_ui->spinBox_subtractFilteringMinPts->value()).toInt());
576 
577  _ui->checkBox_smoothing->setChecked(settings.value("mls", _ui->checkBox_smoothing->isChecked()).toBool());
578  _ui->doubleSpinBox_mlsRadius->setValue(settings.value("mls_radius", _ui->doubleSpinBox_mlsRadius->value()).toDouble());
579  _ui->spinBox_polygonialOrder->setValue(settings.value("mls_polygonial_order", _ui->spinBox_polygonialOrder->value()).toInt());
580  _ui->comboBox_upsamplingMethod->setCurrentIndex(settings.value("mls_upsampling_method", _ui->comboBox_upsamplingMethod->currentIndex()).toInt());
581  _ui->doubleSpinBox_sampleRadius->setValue(settings.value("mls_upsampling_radius", _ui->doubleSpinBox_sampleRadius->value()).toDouble());
582  _ui->doubleSpinBox_sampleStep->setValue(settings.value("mls_upsampling_step", _ui->doubleSpinBox_sampleStep->value()).toDouble());
583  _ui->spinBox_randomPoints->setValue(settings.value("mls_point_density", _ui->spinBox_randomPoints->value()).toInt());
584  _ui->doubleSpinBox_dilationVoxelSize->setValue(settings.value("mls_dilation_voxel_size", _ui->doubleSpinBox_dilationVoxelSize->value()).toDouble());
585  _ui->spinBox_dilationSteps->setValue(settings.value("mls_dilation_iterations", _ui->spinBox_dilationSteps->value()).toInt());
586  _ui->doubleSpinBox_mls_outputVoxelSize->setValue(settings.value("mls_output_voxel_size", _ui->doubleSpinBox_mls_outputVoxelSize->value()).toInt());
587 
588  _ui->checkBox_gainCompensation->setChecked(settings.value("gain", _ui->checkBox_gainCompensation->isChecked()).toBool());
589  _ui->doubleSpinBox_gainRadius->setValue(settings.value("gain_radius", _ui->doubleSpinBox_gainRadius->value()).toDouble());
590  _ui->doubleSpinBox_gainOverlap->setValue(settings.value("gain_overlap", _ui->doubleSpinBox_gainOverlap->value()).toDouble());
591  _ui->doubleSpinBox_gainBeta->setValue(settings.value("gain_beta", _ui->doubleSpinBox_gainBeta->value()).toDouble());
592  _ui->checkBox_gainRGB->setChecked(settings.value("gain_rgb", _ui->checkBox_gainRGB->isChecked()).toBool());
593  _ui->checkBox_gainFull->setChecked(settings.value("gain_full", _ui->checkBox_gainFull->isChecked()).toBool());
594 
595  _ui->checkBox_cameraProjection->setChecked(settings.value("cam_proj", _ui->checkBox_cameraProjection->isChecked()).toBool());
596  _ui->lineEdit_camProjRoiRatios->setText(settings.value("cam_proj_roi_ratios", _ui->lineEdit_camProjRoiRatios->text()).toString());
597  _ui->lineEdit_camProjMaskFilePath->setText(settings.value("cam_proj_mask", _ui->lineEdit_camProjMaskFilePath->text()).toString());
598  _ui->spinBox_camProjDecimation->setValue(settings.value("cam_proj_decimation", _ui->spinBox_camProjDecimation->value()).toInt());
599  _ui->doubleSpinBox_camProjMaxDistance->setValue(settings.value("cam_proj_max_distance", _ui->doubleSpinBox_camProjMaxDistance->value()).toDouble());
600  _ui->doubleSpinBox_camProjMaxAngle->setValue(settings.value("cam_proj_max_angle", _ui->doubleSpinBox_camProjMaxAngle->value()).toDouble());
601  _ui->checkBox_camProjDistanceToCamPolicy->setChecked(settings.value("cam_proj_distance_policy", _ui->checkBox_camProjDistanceToCamPolicy->isChecked()).toBool());
602  _ui->checkBox_camProjKeepPointsNotSeenByCameras->setChecked(settings.value("cam_proj_keep_points", _ui->checkBox_camProjKeepPointsNotSeenByCameras->isChecked()).toBool());
603  _ui->checkBox_camProjRecolorPoints->setChecked(settings.value("cam_proj_recolor_points", _ui->checkBox_camProjRecolorPoints->isChecked()).toBool());
604  _ui->comboBox_camProjExportCamera->setCurrentIndex(settings.value("cam_proj_export_format", _ui->comboBox_camProjExportCamera->currentIndex()).toInt());
605 
606  _ui->checkBox_meshing->setChecked(settings.value("mesh", _ui->checkBox_meshing->isChecked()).toBool());
607  _ui->doubleSpinBox_gp3Radius->setValue(settings.value("mesh_radius", _ui->doubleSpinBox_gp3Radius->value()).toDouble());
608  _ui->doubleSpinBox_gp3Mu->setValue(settings.value("mesh_mu", _ui->doubleSpinBox_gp3Mu->value()).toDouble());
609  _ui->doubleSpinBox_meshDecimationFactor->setValue(settings.value("mesh_decimation_factor",_ui->doubleSpinBox_meshDecimationFactor->value()).toDouble());
610  _ui->spinBox_meshMaxPolygons->setValue(settings.value("mesh_max_polygons",_ui->spinBox_meshMaxPolygons->value()).toDouble());
611  _ui->doubleSpinBox_transferColorRadius->setValue(settings.value("mesh_color_radius",_ui->doubleSpinBox_transferColorRadius->value()).toDouble());
612  _ui->checkBox_cleanMesh->setChecked(settings.value("mesh_clean",_ui->checkBox_cleanMesh->isChecked()).toBool());
613  _ui->spinBox_mesh_minClusterSize->setValue(settings.value("mesh_min_cluster_size", _ui->spinBox_mesh_minClusterSize->value()).toInt());
614 
615  _ui->comboBox_meshingApproach->setCurrentIndex(settings.value("mesh_dense_strategy", _ui->comboBox_meshingApproach->currentIndex()).toInt());
616 
617  _ui->checkBox_textureMapping->setChecked(settings.value("mesh_texture", _ui->checkBox_textureMapping->isChecked()).toBool());
618  _ui->comboBox_meshingTextureFormat->setCurrentIndex(settings.value("mesh_textureFormat", _ui->comboBox_meshingTextureFormat->currentIndex()).toInt());
619  _ui->comboBox_meshingTextureSize->setCurrentIndex(settings.value("mesh_textureSize", _ui->comboBox_meshingTextureSize->currentIndex()).toInt());
620  _ui->spinBox_mesh_maxTextures->setValue(settings.value("mesh_textureMaxCount", _ui->spinBox_mesh_maxTextures->value()).toInt());
621  _ui->doubleSpinBox_meshingTextureMaxDistance->setValue(settings.value("mesh_textureMaxDistance", _ui->doubleSpinBox_meshingTextureMaxDistance->value()).toDouble());
622  _ui->doubleSpinBox_meshingTextureMaxDepthError->setValue(settings.value("mesh_textureMaxDepthError", _ui->doubleSpinBox_meshingTextureMaxDepthError->value()).toDouble());
623  _ui->doubleSpinBox_meshingTextureMaxAngle->setValue(settings.value("mesh_textureMaxAngle", _ui->doubleSpinBox_meshingTextureMaxAngle->value()).toDouble());
624  _ui->spinBox_mesh_minTextureClusterSize->setValue(settings.value("mesh_textureMinCluster", _ui->spinBox_mesh_minTextureClusterSize->value()).toDouble());
625  _ui->lineEdit_meshingTextureRoiRatios->setText(settings.value("mesh_textureRoiRatios", _ui->lineEdit_meshingTextureRoiRatios->text()).toString());
626  _ui->checkBox_distanceToCamPolicy->setChecked(settings.value("mesh_textureDistanceToCamPolicy", _ui->checkBox_distanceToCamPolicy->isChecked()).toBool());
627  _ui->checkBox_cameraFilter->setChecked(settings.value("mesh_textureCameraFiltering", _ui->checkBox_cameraFilter->isChecked()).toBool());
628  _ui->doubleSpinBox_cameraFilterRadius->setValue(settings.value("mesh_textureCameraFilteringRadius", _ui->doubleSpinBox_cameraFilterRadius->value()).toDouble());
629  _ui->doubleSpinBox_cameraFilterAngle->setValue(settings.value("mesh_textureCameraFilteringAngle", _ui->doubleSpinBox_cameraFilterAngle->value()).toDouble());
630  _ui->doubleSpinBox_cameraFilterVel->setValue(settings.value("mesh_textureCameraFilteringVel", _ui->doubleSpinBox_cameraFilterVel->value()).toDouble());
631  _ui->doubleSpinBox_cameraFilterVelRad->setValue(settings.value("mesh_textureCameraFilteringVelRad", _ui->doubleSpinBox_cameraFilterVelRad->value()).toDouble());
632  _ui->doubleSpinBox_laplacianVariance->setValue(settings.value("mesh_textureCameraFilteringLaplacian", _ui->doubleSpinBox_laplacianVariance->value()).toDouble());
633  _ui->spinBox_textureBrightnessContrastRatioLow->setValue(settings.value("mesh_textureBrightnessConstrastRatioLow", _ui->spinBox_textureBrightnessContrastRatioLow->value()).toDouble());
634  _ui->spinBox_textureBrightnessContrastRatioHigh->setValue(settings.value("mesh_textureBrightnessConstrastRatioHigh", _ui->spinBox_textureBrightnessContrastRatioHigh->value()).toDouble());
635  if(_ui->checkBox_exposureFusion->isEnabled())
636  {
637  _ui->checkBox_exposureFusion->setChecked(settings.value("mesh_textureExposureFusion", _ui->checkBox_exposureFusion->isChecked()).toBool());
638  }
639  _ui->checkBox_blending->setChecked(settings.value("mesh_textureBlending", _ui->checkBox_blending->isChecked()).toBool());
640  _ui->comboBox_blendingDecimation->setCurrentIndex(settings.value("mesh_textureBlendingDecimation", _ui->comboBox_blendingDecimation->currentIndex()).toInt());
641  _ui->checkBox_multiband->setChecked(settings.value("mesh_textureMultiband", _ui->checkBox_multiband->isChecked()).toBool());
642  _ui->spinBox_multiband_downscale->setValue(settings.value("mesh_textureMultibandDownScale", _ui->spinBox_multiband_downscale->value()).toInt());
643  _ui->lineEdit_multiband_nbcontrib->setText(settings.value("mesh_textureMultibandNbContrib", _ui->lineEdit_multiband_nbcontrib->text()).toString());
644  _ui->comboBox_multiband_unwrap->setCurrentIndex(settings.value("mesh_textureMultibandUnwrap", _ui->comboBox_multiband_unwrap->currentIndex()).toInt());
645  _ui->checkBox_multiband_fillholes->setChecked(settings.value("mesh_textureMultibandFillHoles", _ui->checkBox_multiband_fillholes->isChecked()).toBool());
646  _ui->spinBox_multiband_padding->setValue(settings.value("mesh_textureMultibandPadding", _ui->spinBox_multiband_padding->value()).toInt());
647  _ui->doubleSpinBox_multiband_bestscore->setValue(settings.value("mesh_textureMultibandBestScoreThr", _ui->doubleSpinBox_multiband_bestscore->value()).toDouble());
648  _ui->doubleSpinBox_multiband_angle->setValue(settings.value("mesh_textureMultibandAngleHardThr", _ui->doubleSpinBox_multiband_angle->value()).toDouble());
649  _ui->checkBox_multiband_forcevisible->setChecked(settings.value("mesh_textureMultibandForceVisible", _ui->checkBox_multiband_forcevisible->isChecked()).toBool());
650 
651  _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value("mesh_angle_tolerance", _ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
652  _ui->checkBox_mesh_quad->setChecked(settings.value("mesh_quad", _ui->checkBox_mesh_quad->isChecked()).toBool());
653  _ui->spinBox_mesh_triangleSize->setValue(settings.value("mesh_triangle_size", _ui->spinBox_mesh_triangleSize->value()).toInt());
654 
655  _ui->checkBox_poisson_outputPolygons->setChecked(settings.value("poisson_outputPolygons", _ui->checkBox_poisson_outputPolygons->isChecked()).toBool());
656  _ui->checkBox_poisson_manifold->setChecked(settings.value("poisson_manifold", _ui->checkBox_poisson_manifold->isChecked()).toBool());
657  _ui->spinBox_poisson_depth->setValue(settings.value("poisson_depth", _ui->spinBox_poisson_depth->value()).toInt());
658  _ui->doubleSpinBox_poisson_targetPolygonSize->setValue(settings.value("poisson_polygon_size", _ui->doubleSpinBox_poisson_targetPolygonSize->value()).toDouble());
659  _ui->spinBox_poisson_iso->setValue(settings.value("poisson_iso", _ui->spinBox_poisson_iso->value()).toInt());
660  _ui->spinBox_poisson_solver->setValue(settings.value("poisson_solver", _ui->spinBox_poisson_solver->value()).toInt());
661  _ui->spinBox_poisson_minDepth->setValue(settings.value("poisson_minDepth", _ui->spinBox_poisson_minDepth->value()).toInt());
662  _ui->doubleSpinBox_poisson_samples->setValue(settings.value("poisson_samples", _ui->doubleSpinBox_poisson_samples->value()).toDouble());
663  _ui->doubleSpinBox_poisson_pointWeight->setValue(settings.value("poisson_pointWeight", _ui->doubleSpinBox_poisson_pointWeight->value()).toDouble());
664  _ui->doubleSpinBox_poisson_scale->setValue(settings.value("poisson_scale", _ui->doubleSpinBox_poisson_scale->value()).toDouble());
665 
666  _ui->doubleSpinBox_cputsdf_size->setValue(settings.value("cputsdf_size", _ui->doubleSpinBox_cputsdf_size->value()).toDouble());
667  _ui->doubleSpinBox_cputsdf_resolution->setValue(settings.value("cputsdf_resolution", _ui->doubleSpinBox_cputsdf_resolution->value()).toDouble());
668  _ui->doubleSpinBox_cputsdf_tuncPos->setValue(settings.value("cputsdf_truncPos", _ui->doubleSpinBox_cputsdf_tuncPos->value()).toDouble());
669  _ui->doubleSpinBox_cputsdf_tuncNeg->setValue(settings.value("cputsdf_truncNeg", _ui->doubleSpinBox_cputsdf_tuncNeg->value()).toDouble());
670  _ui->doubleSpinBox_cputsdf_minWeight->setValue(settings.value("cputsdf_minWeight", _ui->doubleSpinBox_cputsdf_minWeight->value()).toDouble());
671  _ui->doubleSpinBox_cputsdf_flattenRadius->setValue(settings.value("cputsdf_flattenRadius", _ui->doubleSpinBox_cputsdf_flattenRadius->value()).toDouble());
672  _ui->spinBox_cputsdf_randomSplit->setValue(settings.value("cputsdf_randomSplit", _ui->spinBox_cputsdf_randomSplit->value()).toInt());
673 
674  _ui->checkBox_openchisel_mergeVertices->setChecked(settings.value("openchisel_merge_vertices", _ui->checkBox_openchisel_mergeVertices->isChecked()).toBool());
675  _ui->spinBox_openchisel_chunk_size_x->setValue(settings.value("openchisel_chunk_size_x", _ui->spinBox_openchisel_chunk_size_x->value()).toInt());
676  _ui->spinBox_openchisel_chunk_size_y->setValue(settings.value("openchisel_chunk_size_y", _ui->spinBox_openchisel_chunk_size_y->value()).toInt());
677  _ui->spinBox_openchisel_chunk_size_z->setValue(settings.value("openchisel_chunk_size_z", _ui->spinBox_openchisel_chunk_size_z->value()).toInt());
678  _ui->doubleSpinBox_openchisel_truncation_constant->setValue(settings.value("openchisel_truncation_constant", _ui->doubleSpinBox_openchisel_truncation_constant->value()).toDouble());
679  _ui->doubleSpinBox_openchisel_truncation_linear->setValue(settings.value("openchisel_truncation_linear", _ui->doubleSpinBox_openchisel_truncation_linear->value()).toDouble());
680  _ui->doubleSpinBox_openchisel_truncation_quadratic->setValue(settings.value("openchisel_truncation_quadratic", _ui->doubleSpinBox_openchisel_truncation_quadratic->value()).toDouble());
681  _ui->doubleSpinBox_openchisel_truncation_scale->setValue(settings.value("openchisel_truncation_scale", _ui->doubleSpinBox_openchisel_truncation_scale->value()).toDouble());
682  _ui->spinBox_openchisel_integration_weight->setValue(settings.value("openchisel_integration_weight", _ui->spinBox_openchisel_integration_weight->value()).toInt());
683  _ui->checkBox_openchisel_use_voxel_carving->setChecked(settings.value("openchisel_use_voxel_carving", _ui->checkBox_openchisel_use_voxel_carving->isChecked()).toBool());
684  _ui->doubleSpinBox_openchisel_carving_dist_m->setValue(settings.value("openchisel_carving_dist_m", _ui->doubleSpinBox_openchisel_carving_dist_m->value()).toDouble());
685  _ui->doubleSpinBox_openchisel_near_plane_dist->setValue(settings.value("openchisel_near_plane_dist", _ui->doubleSpinBox_openchisel_near_plane_dist->value()).toDouble());
686  _ui->doubleSpinBox_openchisel_far_plane_dist->setValue(settings.value("openchisel_far_plane_dist", _ui->doubleSpinBox_openchisel_far_plane_dist->value()).toDouble());
687 
690 
691  if(!group.isEmpty())
692  {
693  settings.endGroup();
694  }
695 }
696 
698 {
699  _ui->comboBox_pipeline->setCurrentIndex(1);
700  _ui->checkBox_fromDepth->setChecked(true);
701  _ui->checkBox_binary->setChecked(true);
702  _ui->spinBox_normalKSearch->setValue(20);
703  _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
704  _ui->doubleSpinBox_groundNormalsUp->setValue(0.0);
705  _ui->comboBox_intensityColormap->setCurrentIndex(0);
706 
707  _ui->checkBox_nodes_filtering->setChecked(false);
708  _ui->doubleSpinBox_nodes_filtering_xmin->setValue(0);
709  _ui->doubleSpinBox_nodes_filtering_xmax->setValue(0);
710  _ui->doubleSpinBox_nodes_filtering_ymin->setValue(0);
711  _ui->doubleSpinBox_nodes_filtering_ymax->setValue(0);
712  _ui->doubleSpinBox_nodes_filtering_zmin->setValue(0);
713  _ui->doubleSpinBox_nodes_filtering_zmax->setValue(0);
714 
715  _ui->checkBox_regenerate->setChecked(_dbDriver!=0?true:false);
716  _ui->spinBox_decimation->setValue(1);
717  _ui->doubleSpinBox_maxDepth->setValue(4);
718  _ui->doubleSpinBox_minDepth->setValue(0);
719  _ui->doubleSpinBox_ceilingHeight->setValue(0);
720  _ui->doubleSpinBox_floorHeight->setValue(0);
721  _ui->doubleSpinBox_footprintHeight->setValue(0);
722  _ui->doubleSpinBox_footprintLength->setValue(0);
723  _ui->doubleSpinBox_footprintWidth->setValue(0);
724  _ui->spinBox_decimation_scan->setValue(1);
725  _ui->doubleSpinBox_rangeMax->setValue(0);
726  _ui->doubleSpinBox_rangeMin->setValue(0);
727  _ui->spinBox_fillDepthHoles->setValue(0);
728  _ui->spinBox_fillDepthHolesError->setValue(2);
729  _ui->lineEdit_roiRatios->setText("0.0 0.0 0.0 0.0");
730  _ui->lineEdit_distortionModel->setText("");
731 
732  _ui->checkBox_bilateral->setChecked(false);
733  _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
734  _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
735 
736  _ui->checkBox_filtering->setChecked(false);
737  _ui->doubleSpinBox_filteringRadius->setValue(0.00);
738  _ui->spinBox_filteringMinNeighbors->setValue(5);
739 
740  _ui->checkBox_assemble->setChecked(true);
741  _ui->doubleSpinBox_voxelSize_assembled->setValue(0.01);
742  _ui->spinBox_randomSamples_assembled->setValue(0);
743  _ui->comboBox_frame->setCurrentIndex(0);
744 
745  _ui->checkBox_subtraction->setChecked(false);
746  _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(0.02);
747  _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(0);
748  _ui->spinBox_subtractFilteringMinPts->setValue(5);
749 
750  _ui->checkBox_smoothing->setChecked(false);
751  _ui->doubleSpinBox_mlsRadius->setValue(0.04);
752  _ui->spinBox_polygonialOrder->setValue(2);
753  _ui->comboBox_upsamplingMethod->setCurrentIndex(0);
754  _ui->doubleSpinBox_sampleRadius->setValue(0.01);
755  _ui->doubleSpinBox_sampleStep->setValue(0.005);
756  _ui->spinBox_randomPoints->setValue(10);
757  _ui->doubleSpinBox_dilationVoxelSize->setValue(0.005);
758  _ui->spinBox_dilationSteps->setValue(1);
759  _ui->doubleSpinBox_mls_outputVoxelSize->setValue(0);
760 
761  _ui->checkBox_gainCompensation->setChecked(false);
762  _ui->doubleSpinBox_gainRadius->setValue(0.02);
763  _ui->doubleSpinBox_gainOverlap->setValue(0.0);
764  _ui->doubleSpinBox_gainBeta->setValue(10);
765  _ui->checkBox_gainRGB->setChecked(true);
766  _ui->checkBox_gainFull->setChecked(false);
767 
768  _ui->checkBox_cameraProjection->setChecked(false);
769  _ui->lineEdit_camProjRoiRatios->setText("0.0 0.0 0.0 0.0");
770  _ui->lineEdit_camProjMaskFilePath->setText("");
771  _ui->spinBox_camProjDecimation->setValue(1);
772  _ui->doubleSpinBox_camProjMaxDistance->setValue(0);
773  _ui->doubleSpinBox_camProjMaxAngle->setValue(0);
774  _ui->checkBox_camProjDistanceToCamPolicy->setChecked(true);
775  _ui->checkBox_camProjKeepPointsNotSeenByCameras->setChecked(false);
776  _ui->checkBox_camProjRecolorPoints->setChecked(true);
777  _ui->comboBox_camProjExportCamera->setCurrentIndex(0);
778 
779  _ui->checkBox_meshing->setChecked(false);
780  _ui->doubleSpinBox_gp3Radius->setValue(0.2);
781  _ui->doubleSpinBox_gp3Mu->setValue(2.5);
782  _ui->doubleSpinBox_meshDecimationFactor->setValue(0.0);
783  _ui->spinBox_meshMaxPolygons->setValue(0);
784  _ui->doubleSpinBox_transferColorRadius->setValue(0.025);
785  _ui->checkBox_cleanMesh->setChecked(true);
786  _ui->spinBox_mesh_minClusterSize->setValue(0);
787 
788  _ui->comboBox_meshingApproach->setCurrentIndex(1);
789 
790  _ui->checkBox_textureMapping->setChecked(false);
791  _ui->comboBox_meshingTextureFormat->setCurrentIndex(0);
792  _ui->comboBox_meshingTextureSize->setCurrentIndex(6); // 8192
793  _ui->spinBox_mesh_maxTextures->setValue(1);
794  _ui->doubleSpinBox_meshingTextureMaxDistance->setValue(3.0);
795  _ui->doubleSpinBox_meshingTextureMaxDepthError->setValue(0.0);
796  _ui->doubleSpinBox_meshingTextureMaxAngle->setValue(0.0);
797  _ui->spinBox_mesh_minTextureClusterSize->setValue(50);
798  _ui->lineEdit_meshingTextureRoiRatios->setText("0.0 0.0 0.0 0.0");
799  _ui->checkBox_distanceToCamPolicy->setChecked(false);
800  _ui->checkBox_cameraFilter->setChecked(false);
801  _ui->doubleSpinBox_cameraFilterRadius->setValue(0);
802  _ui->doubleSpinBox_cameraFilterAngle->setValue(30);
803  _ui->doubleSpinBox_cameraFilterVel->setValue(0);
804  _ui->doubleSpinBox_cameraFilterVelRad->setValue(0);
805  _ui->doubleSpinBox_laplacianVariance->setValue(0);
806  _ui->spinBox_textureBrightnessContrastRatioLow->setValue(0);
807  _ui->spinBox_textureBrightnessContrastRatioHigh->setValue(5);
808  _ui->checkBox_exposureFusion->setChecked(false);
809  _ui->checkBox_blending->setChecked(true);
810  _ui->comboBox_blendingDecimation->setCurrentIndex(0);
811  _ui->checkBox_multiband->setChecked(false);
812  _ui->spinBox_multiband_downscale->setValue(2);
813  _ui->lineEdit_multiband_nbcontrib->setText("1 5 10 0");
814  _ui->comboBox_multiband_unwrap->setCurrentIndex(0);
815  _ui->checkBox_multiband_fillholes->setChecked(false);
816  _ui->spinBox_multiband_padding->setValue(5);
817  _ui->doubleSpinBox_multiband_bestscore->setValue(0.1);
818  _ui->doubleSpinBox_multiband_angle->setValue(90.0);
819  _ui->checkBox_multiband_forcevisible->setChecked(false);
820 
821 
822  _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
823  _ui->checkBox_mesh_quad->setChecked(false);
824  _ui->spinBox_mesh_triangleSize->setValue(1);
825 
826  _ui->checkBox_poisson_outputPolygons->setChecked(false);
827  _ui->checkBox_poisson_manifold->setChecked(true);
828  _ui->spinBox_poisson_depth->setValue(0);
829  _ui->doubleSpinBox_poisson_targetPolygonSize->setValue(0.03);
830  _ui->spinBox_poisson_iso->setValue(8);
831  _ui->spinBox_poisson_solver->setValue(8);
832  _ui->spinBox_poisson_minDepth->setValue(5);
833  _ui->doubleSpinBox_poisson_samples->setValue(1.0);
834  _ui->doubleSpinBox_poisson_pointWeight->setValue(4.0);
835  _ui->doubleSpinBox_poisson_scale->setValue(1.1);
836 
837  _ui->doubleSpinBox_cputsdf_size->setValue(12.0);
838  _ui->doubleSpinBox_cputsdf_resolution->setValue(0.01);
839  _ui->doubleSpinBox_cputsdf_tuncPos->setValue(0.03);
840  _ui->doubleSpinBox_cputsdf_tuncNeg->setValue(0.03);
841  _ui->doubleSpinBox_cputsdf_minWeight->setValue(0);
842  _ui->doubleSpinBox_cputsdf_flattenRadius->setValue(0.005);
843  _ui->spinBox_cputsdf_randomSplit->setValue(1);
844 
845  _ui->checkBox_openchisel_mergeVertices->setChecked(true);
846  _ui->spinBox_openchisel_chunk_size_x->setValue(16);
847  _ui->spinBox_openchisel_chunk_size_y->setValue(16);
848  _ui->spinBox_openchisel_chunk_size_z->setValue(16);
849  _ui->doubleSpinBox_openchisel_truncation_constant->setValue(0.001504);
850  _ui->doubleSpinBox_openchisel_truncation_linear->setValue(0.00152);
851  _ui->doubleSpinBox_openchisel_truncation_quadratic->setValue(0.0019);
852  _ui->doubleSpinBox_openchisel_truncation_scale->setValue(10.0);
853  _ui->spinBox_openchisel_integration_weight->setValue(1);
854  _ui->checkBox_openchisel_use_voxel_carving->setChecked(false);
855  _ui->doubleSpinBox_openchisel_carving_dist_m->setValue(0.05);
856  _ui->doubleSpinBox_openchisel_near_plane_dist->setValue(0.05);
857  _ui->doubleSpinBox_openchisel_far_plane_dist->setValue(1.1);
858 
859 
862 
863  this->update();
864 }
865 
867 {
868  QString path = QFileDialog::getOpenFileName(this, tr("Load Settings"), _workingDirectory, tr("Config (*.ini)"));
869  if(path.size())
870  {
871  QSettings settings(path, QSettings::IniFormat);
872  settings.beginGroup("Gui");
873  settings.beginGroup(this->objectName());
874  this->loadSettings(settings);
875  settings.endGroup(); // "name"
876  settings.endGroup(); // Gui
877  }
878 }
879 
881 {
882  QString path = QFileDialog::getSaveFileName(this, tr("Save Settings"), _workingDirectory, tr("Config (*.ini)"));
883  if(path.size())
884  {
885  QSettings settings(path, QSettings::IniFormat);
886  settings.beginGroup("Gui");
887  settings.beginGroup(this->objectName());
888  this->saveSettings(settings);
889  settings.endGroup(); // "name"
890  settings.endGroup(); // Gui
891  }
892 }
893 
895 {
896  if(!_ui->checkBox_fromDepth->isChecked())
897  {
898  _ui->comboBox_pipeline->setCurrentIndex(1);
899  _ui->comboBox_pipeline->setEnabled(false);
900  _ui->comboBox_frame->setItemData(2, 0,Qt::UserRole - 1);
901  _ui->comboBox_frame->setItemData(3, 1|32,Qt::UserRole - 1);
902  if(_ui->comboBox_frame->currentIndex() == 2)
903  {
904  _ui->comboBox_frame->setCurrentIndex(0);
905  }
906  }
907  else
908  {
909  _ui->comboBox_pipeline->setEnabled(true);
910  _ui->comboBox_frame->setItemData(2, 1|32,Qt::UserRole - 1);
911  _ui->comboBox_frame->setItemData(3, 0,Qt::UserRole - 1);
912  if(_ui->comboBox_frame->currentIndex() == 3)
913  {
914  _ui->comboBox_frame->setCurrentIndex(0);
915  }
916  }
917  _ui->comboBox_intensityColormap->setVisible(!_ui->checkBox_fromDepth->isChecked() && !_ui->checkBox_binary->isEnabled());
918  _ui->comboBox_intensityColormap->setEnabled(!_ui->checkBox_fromDepth->isChecked() && !_ui->checkBox_binary->isEnabled());
919  _ui->label_intensityColormap->setVisible(!_ui->checkBox_fromDepth->isChecked() && !_ui->checkBox_binary->isEnabled());
920 
921  _ui->checkBox_smoothing->setVisible(_ui->comboBox_pipeline->currentIndex() == 1);
922  _ui->checkBox_smoothing->setEnabled(_ui->comboBox_pipeline->currentIndex() == 1);
923  _ui->label_smoothing->setVisible(_ui->comboBox_pipeline->currentIndex() == 1);
924 
925  _ui->comboBox_frame->setEnabled(!_ui->checkBox_assemble->isChecked() && _ui->checkBox_binary->isEnabled());
926  _ui->comboBox_frame->setVisible(_ui->comboBox_frame->isEnabled());
927  _ui->label_frame->setVisible(_ui->comboBox_frame->isEnabled());
928  _ui->checkBox_gainCompensation->setEnabled(!(_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex() == 2));
929  _ui->checkBox_gainCompensation->setVisible(_ui->checkBox_gainCompensation->isEnabled());
930  _ui->label_gainCompensation->setVisible(_ui->checkBox_gainCompensation->isEnabled());
931 
932  _ui->checkBox_cameraProjection->setEnabled(_ui->checkBox_assemble->isChecked() && !_ui->checkBox_meshing->isChecked());
933  _ui->label_cameraProjection->setEnabled(_ui->checkBox_cameraProjection->isEnabled());
934 
935  _ui->groupBox_nodes_filtering->setVisible(_ui->checkBox_nodes_filtering->isChecked());
936  _ui->groupBox_regenerate->setVisible(_ui->checkBox_regenerate->isChecked() && _ui->checkBox_fromDepth->isChecked());
937  _ui->groupBox_regenerateScans->setVisible(_ui->checkBox_regenerate->isChecked() && !_ui->checkBox_fromDepth->isChecked());
938  _ui->groupBox_bilateral->setVisible(_ui->checkBox_bilateral->isChecked());
939  _ui->groupBox_filtering->setVisible(_ui->checkBox_filtering->isChecked());
940  _ui->groupBox_gain->setVisible(_ui->checkBox_gainCompensation->isEnabled() && _ui->checkBox_gainCompensation->isChecked());
941  _ui->groupBox_cameraProjection->setVisible(_ui->checkBox_cameraProjection->isEnabled() && _ui->checkBox_cameraProjection->isChecked());
942  _ui->groupBox_mls->setVisible(_ui->checkBox_smoothing->isEnabled() && _ui->checkBox_smoothing->isChecked());
943  _ui->groupBox_meshing->setVisible(_ui->checkBox_meshing->isChecked());
944  _ui->groupBox_subtraction->setVisible(_ui->checkBox_subtraction->isChecked());
945  _ui->groupBox_textureMapping->setVisible(_ui->checkBox_textureMapping->isChecked());
946  _ui->groupBox_cameraFilter->setVisible(_ui->checkBox_cameraFilter->isChecked());
947  _ui->groupBox_multiband->setVisible(_ui->checkBox_multiband->isChecked());
948 
949  // dense texturing options
950  if(_ui->checkBox_meshing->isChecked())
951  {
952  //GP3
953  _ui->comboBox_meshingApproach->setItemData(0, _ui->comboBox_pipeline->currentIndex() == 1?1 | 32:0,Qt::UserRole - 1);
954 
955  //Poisson
956  _ui->comboBox_meshingApproach->setItemData(1, _ui->comboBox_pipeline->currentIndex() == 1 && _ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
957 
958  //CPU-TSDF
959 #ifdef RTABMAP_CPUTSDF
960  _ui->comboBox_meshingApproach->setItemData(2, _ui->comboBox_pipeline->currentIndex() == 0 && _ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
961 #else
962  _ui->comboBox_meshingApproach->setItemData(2, 0, Qt::UserRole - 1);
963 #endif
964 
965  // Organized
966  _ui->comboBox_meshingApproach->setItemData(3, _ui->comboBox_pipeline->currentIndex() == 0?1 | 32:0,Qt::UserRole - 1);
967 
968  //Open Chisel
969 #ifdef RTABMAP_OPENCHISEL
970  _ui->comboBox_meshingApproach->setItemData(4, _ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
971 #else
972  _ui->comboBox_meshingApproach->setItemData(4, 0, Qt::UserRole - 1);
973 #endif
974 
975  if(_ui->comboBox_pipeline->currentIndex() == 0 && _ui->comboBox_meshingApproach->currentIndex()<2)
976  {
977  _ui->comboBox_meshingApproach->setCurrentIndex(3);
978  }
979  if(_ui->comboBox_pipeline->currentIndex() == 1 && (_ui->comboBox_meshingApproach->currentIndex()==2 || _ui->comboBox_meshingApproach->currentIndex()==3))
980  {
981  _ui->comboBox_meshingApproach->setCurrentIndex(1);
982  }
983  if(!_ui->checkBox_assemble->isChecked())
984  {
985  _ui->comboBox_meshingApproach->setCurrentIndex(_ui->comboBox_pipeline->currentIndex() == 1?0:3);
986  }
987 
988  _ui->checkBox_poisson_outputPolygons->setDisabled(
989  _ui->checkBox_binary->isEnabled() ||
990  _ui->doubleSpinBox_meshDecimationFactor->value()!=0.0 ||
991  _ui->spinBox_meshMaxPolygons->value()!=0 ||
992  _ui->checkBox_textureMapping->isChecked());
993  _ui->label_outputPolygons->setEnabled(_ui->checkBox_poisson_outputPolygons->isEnabled());
994 
995  _ui->checkBox_cleanMesh->setEnabled(_ui->comboBox_pipeline->currentIndex() == 1);
996  _ui->label_meshClean->setEnabled(_ui->comboBox_pipeline->currentIndex() == 1);
997 
998  _ui->groupBox_gp3->setVisible(_ui->comboBox_pipeline->currentIndex() == 1 && _ui->comboBox_meshingApproach->currentIndex()==0);
999  _ui->groupBox_poisson->setVisible(_ui->comboBox_pipeline->currentIndex() == 1 && _ui->comboBox_meshingApproach->currentIndex()==1);
1000  _ui->groupBox_cputsdf->setVisible(_ui->comboBox_pipeline->currentIndex() == 0 && _ui->comboBox_meshingApproach->currentIndex()==2);
1001  _ui->groupBox_organized->setVisible(_ui->comboBox_pipeline->currentIndex() == 0 && _ui->comboBox_meshingApproach->currentIndex()==3);
1002  _ui->groupBox_openchisel->setVisible(_ui->comboBox_meshingApproach->currentIndex()==4);
1003 
1004 #ifndef DISABLE_VTK
1005  _ui->doubleSpinBox_meshDecimationFactor->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
1006  _ui->label_meshDecimation->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
1007  _ui->spinBox_meshMaxPolygons->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
1008  _ui->label_meshMaxPolygons->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
1009 #endif
1010 
1011 #ifndef RTABMAP_ALICE_VISION
1012  _ui->checkBox_multiband->setEnabled(false);
1013 #else
1014  _ui->checkBox_multiband->setEnabled(_ui->checkBox_binary->isEnabled());
1015 #endif
1016  _ui->label_multiband->setEnabled(_ui->checkBox_multiband->isEnabled());
1017  }
1018 }
1019 
1021 {
1022  QString dir = _ui->lineEdit_distortionModel->text();
1023  if(dir.isEmpty())
1024  {
1025  dir = _workingDirectory;
1026  }
1027  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Distortion model (*.bin *.txt)"));
1028  if(path.size())
1029  {
1030  _ui->lineEdit_distortionModel->setText(path);
1031  }
1032 }
1033 
1035 {
1036  QString dir = _ui->lineEdit_camProjMaskFilePath->text();
1037  if(dir.isEmpty())
1038  {
1039  dir = _workingDirectory;
1040  }
1041  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Mask (grayscale) (*.png *.pgm *bmp)"));
1042  if(path.size())
1043  {
1044  _ui->lineEdit_camProjMaskFilePath->setText(path);
1045  }
1046 }
1047 
1049 {
1050  _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(false);
1051  _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(true);
1052  _ui->checkBox_binary->setVisible(true);
1053  _ui->checkBox_binary->setEnabled(true);
1054  _ui->label_binaryFile->setVisible(true);
1055  _ui->checkBox_mesh_quad->setVisible(false);
1056  _ui->checkBox_mesh_quad->setEnabled(false);
1057  _ui->label_quad->setVisible(false);
1059 }
1060 
1062 {
1063  _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(true);
1064  _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(false);
1065  _ui->checkBox_binary->setVisible(false);
1066  _ui->checkBox_binary->setEnabled(false);
1067  _ui->label_binaryFile->setVisible(false);
1068  _ui->checkBox_mesh_quad->setVisible(true);
1069  _ui->checkBox_mesh_quad->setEnabled(true);
1070  _ui->label_quad->setVisible(true);
1072 }
1073 
1074 std::map<int, Transform> ExportCloudsDialog::filterNodes(const std::map<int, Transform> & poses)
1075 {
1076  if(_ui->checkBox_nodes_filtering->isChecked())
1077  {
1078  std::map<int, Transform> posesFiltered;
1079  for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
1080  {
1081  bool ignore = false;
1082  if(_ui->doubleSpinBox_nodes_filtering_xmin->value() != _ui->doubleSpinBox_nodes_filtering_xmax->value() &&
1083  (iter->second.x() < _ui->doubleSpinBox_nodes_filtering_xmin->value() ||
1084  iter->second.x() > _ui->doubleSpinBox_nodes_filtering_xmax->value()))
1085  {
1086  ignore = true;
1087  }
1088  if(_ui->doubleSpinBox_nodes_filtering_ymin->value() != _ui->doubleSpinBox_nodes_filtering_ymax->value() &&
1089  (iter->second.y() < _ui->doubleSpinBox_nodes_filtering_ymin->value() ||
1090  iter->second.y() > _ui->doubleSpinBox_nodes_filtering_ymax->value()))
1091  {
1092  ignore = true;
1093  }
1094  if(_ui->doubleSpinBox_nodes_filtering_zmin->value() != _ui->doubleSpinBox_nodes_filtering_zmax->value() &&
1095  (iter->second.z() < _ui->doubleSpinBox_nodes_filtering_zmin->value() ||
1096  iter->second.z() > _ui->doubleSpinBox_nodes_filtering_zmax->value()))
1097  {
1098  ignore = true;
1099  }
1100  if(!ignore)
1101  {
1102  posesFiltered.insert(*iter);
1103  }
1104  }
1105  return posesFiltered;
1106  }
1107  return poses;
1108 }
1109 
1111  const std::map<int, Transform> & poses,
1112  const std::multimap<int, Link> & links,
1113  const std::map<int, int> & mapIds,
1114  const QMap<int, Signature> & cachedSignatures,
1115  const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
1116  const std::map<int, LaserScan> & cachedScans,
1117  const QString & workingDirectory,
1118  const ParametersMap & parameters)
1119 {
1120  std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
1121  std::map<int, pcl::PolygonMesh::Ptr> meshes;
1122  std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
1123  std::vector<std::map<int, pcl::PointXY> > textureVertexToPixels;
1124 
1125  setSaveButton();
1126 
1127  if(getExportedClouds(
1128  poses,
1129  links,
1130  mapIds,
1131  cachedSignatures,
1132  cachedClouds,
1133  cachedScans,
1134  workingDirectory,
1135  parameters,
1136  clouds,
1137  meshes,
1138  textureMeshes,
1139  textureVertexToPixels))
1140  {
1141  if(textureMeshes.size())
1142  {
1143  saveTextureMeshes(workingDirectory, poses, textureMeshes, cachedSignatures, textureVertexToPixels);
1144  }
1145  else if(meshes.size())
1146  {
1147  bool exportMeshes = true;
1148  if(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked())
1149  {
1150  QMessageBox::StandardButton r = QMessageBox::warning(this, tr("Exporting Texture Mesh"),
1151  tr("No texture mesh could be created, do you want to continue with saving only the meshes (%1)?").arg(meshes.size()),
1152  QMessageBox::Yes|QMessageBox::No, QMessageBox::Yes);
1153  exportMeshes = r == QMessageBox::Yes;
1154  }
1155  if(exportMeshes)
1156  {
1157  saveMeshes(workingDirectory, poses, meshes, _ui->checkBox_binary->isChecked());
1158  }
1159  }
1160  else
1161  {
1162  saveClouds(workingDirectory, poses, clouds, _ui->checkBox_binary->isChecked(), textureVertexToPixels);
1163  }
1164  }
1165  else if(!_canceled)
1166  {
1167  _progressDialog->setAutoClose(false);
1168  }
1170 }
1171 
1173  const std::map<int, Transform> & poses,
1174  const std::multimap<int, Link> & links,
1175  const std::map<int, int> & mapIds,
1176  const QMap<int, Signature> & cachedSignatures,
1177  const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
1178  const std::map<int, LaserScan> & cachedScans,
1179  const QString & workingDirectory,
1180  const ParametersMap & parameters)
1181 {
1182  std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
1183  std::map<int, pcl::PolygonMesh::Ptr> meshes;
1184  std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
1185  std::vector<std::map<int, pcl::PointXY> > textureVertexToPixels;
1186 
1187  setOkButton();
1188 
1189  if(getExportedClouds(
1190  poses,
1191  links,
1192  mapIds,
1193  cachedSignatures,
1194  cachedClouds,
1195  cachedScans,
1196  workingDirectory,
1197  parameters,
1198  clouds,
1199  meshes,
1200  textureMeshes,
1201  textureVertexToPixels))
1202  {
1203  QDialog * window = new QDialog(this->parentWidget()?this->parentWidget():this, Qt::Window);
1204  window->setAttribute(Qt::WA_DeleteOnClose, true);
1205  if(meshes.size())
1206  {
1207  window->setWindowTitle(tr("Meshes (%1 nodes)").arg(meshes.size()));
1208  }
1209  else
1210  {
1211  window->setWindowTitle(tr("Clouds (%1 nodes)").arg(clouds.size()));
1212  }
1213  window->setMinimumWidth(120);
1214  window->setMinimumHeight(90);
1215  window->resize(QDesktopWidget().availableGeometry(this).size() * 0.7);
1216 
1217  CloudViewer * viewer = new CloudViewer(window);
1218  if(_ui->comboBox_pipeline->currentIndex() == 0)
1219  {
1220  viewer->setBackfaceCulling(true, false);
1221  }
1222  viewer->setLighting(false);
1223  viewer->setDefaultBackgroundColor(QColor(40, 40, 40, 255));
1224  viewer->buildPickingLocator(true);
1225  if(_ui->comboBox_intensityColormap->currentIndex()==1)
1226  {
1227  viewer->setIntensityRedColormap(true);
1228  }
1229  else if(_ui->comboBox_intensityColormap->currentIndex() == 2)
1230  {
1231  viewer->setIntensityRainbowColormap(true);
1232  }
1233 
1234  QVBoxLayout *layout = new QVBoxLayout();
1235  layout->addWidget(viewer);
1236  layout->setContentsMargins(0,0,0,0);
1237  window->setLayout(layout);
1238  connect(window, SIGNAL(finished(int)), viewer, SLOT(clear()));
1239 
1240  window->show();
1241 
1242  _progressDialog->appendText(tr("Opening visualizer..."));
1243  QApplication::processEvents();
1244  uSleep(500);
1245  QApplication::processEvents();
1246 
1247  if(textureMeshes.size())
1248  {
1249  viewer->setPolygonPicking(true);
1250  std::map<int, cv::Mat> images;
1251  std::map<int, std::vector<CameraModel> > calibrations;
1252  for(QMap<int, Signature>::const_iterator iter=cachedSignatures.constBegin(); iter!=cachedSignatures.constEnd(); ++iter)
1253  {
1254  std::vector<CameraModel> models;
1255  if(iter->sensorData().cameraModels().size())
1256  {
1257  models = iter->sensorData().cameraModels();
1258  }
1259  else if(iter->sensorData().stereoCameraModels().size())
1260  {
1261  for(size_t i=0; i<iter->sensorData().stereoCameraModels().size(); ++i)
1262  {
1263  models.push_back(iter->sensorData().stereoCameraModels()[i].left());
1264  }
1265  }
1266 
1267  if(!models.empty())
1268  {
1269  if(!iter->sensorData().imageRaw().empty())
1270  {
1271  calibrations.insert(std::make_pair(iter.key(), models));
1272  images.insert(std::make_pair(iter.key(), iter->sensorData().imageRaw()));
1273  }
1274  else if(!iter->sensorData().imageCompressed().empty())
1275  {
1276  calibrations.insert(std::make_pair(iter.key(), models));
1277  images.insert(std::make_pair(iter.key(), iter->sensorData().imageCompressed()));
1278  }
1279  }
1280  }
1281  int textureSize = 1024;
1282  if(_ui->comboBox_meshingTextureSize->currentIndex() > 0)
1283  {
1284  textureSize = 128 << _ui->comboBox_meshingTextureSize->currentIndex(); // start at 256
1285  }
1286  int blendingDecimation = 0;
1287  if(_ui->checkBox_blending->isChecked())
1288  {
1289  if(_ui->comboBox_blendingDecimation->currentIndex() > 0)
1290  {
1291  blendingDecimation = 1 << (_ui->comboBox_blendingDecimation->currentIndex()-1);
1292  }
1293  }
1294 
1295  for (std::map<int, pcl::TextureMesh::Ptr>::iterator iter = textureMeshes.begin(); iter != textureMeshes.end(); ++iter)
1296  {
1297  pcl::TextureMesh::Ptr mesh = iter->second;
1298 
1299  // As CloudViewer is not supporting more than one texture per mesh, merge them all by default
1300  cv::Mat globalTexture;
1301  if (mesh->tex_materials.size() > 1)
1302  {
1303  cv::Mat globalTextures;
1304  globalTextures = util3d::mergeTextures(
1305  *mesh,
1306  images,
1307  calibrations,
1308  0,
1309  _dbDriver,
1310  textureSize,
1311  1,
1312  textureVertexToPixels,
1313  _ui->checkBox_gainCompensation->isChecked(),
1314  _ui->doubleSpinBox_gainBeta->value(),
1315  _ui->checkBox_gainRGB->isChecked(),
1316  _ui->checkBox_blending->isChecked(),
1317  blendingDecimation,
1318  _ui->spinBox_textureBrightnessContrastRatioLow->value(),
1319  _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
1320  _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked());
1321  if(globalTextures.rows == globalTextures.cols)
1322  {
1323  globalTexture = globalTextures;
1324  }
1325  }
1326 
1327  _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)...").arg(iter->first).arg(mesh->tex_polygons.size()?mesh->tex_polygons[0].size():0));
1329 
1330  // VTK issue:
1331  // tex_coordinates should be linked to points, not
1332  // polygon vertices. Points linked to multiple different TCoords (different textures) should
1333  // be duplicated.
1334  for (unsigned int t = 0; t < mesh->tex_coordinates.size(); ++t)
1335  {
1336  if(mesh->tex_polygons[t].size())
1337  {
1338 
1339  pcl::PointCloud<pcl::PointXYZ>::Ptr originalCloud(new pcl::PointCloud<pcl::PointXYZ>);
1340  pcl::fromPCLPointCloud2(mesh->cloud, *originalCloud);
1341 
1342  // make a cloud with as many points than polygon vertices
1343  unsigned int nPoints = mesh->tex_coordinates[t].size();
1344  UASSERT(nPoints == mesh->tex_polygons[t].size()*mesh->tex_polygons[t][0].vertices.size()); // assuming polygon size is constant!
1345 
1346  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
1347  cloud->resize(nPoints);
1348 
1349  unsigned int oi = 0;
1350  for (unsigned int i = 0; i < mesh->tex_polygons[t].size(); ++i)
1351  {
1352  pcl::Vertices & vertices = mesh->tex_polygons[t][i];
1353 
1354  for(unsigned int j=0; j<vertices.vertices.size(); ++j)
1355  {
1356  UASSERT(oi < cloud->size());
1357  UASSERT_MSG((int)vertices.vertices[j] < (int)originalCloud->size(), uFormat("%d vs %d", vertices.vertices[j], (int)originalCloud->size()).c_str());
1358  cloud->at(oi) = originalCloud->at(vertices.vertices[j]);
1359  vertices.vertices[j] = oi; // new vertice index
1360  ++oi;
1361  }
1362  }
1363  pcl::toPCLPointCloud2(*cloud, mesh->cloud);
1364  }
1365  else
1366  {
1367  UWARN("No polygons for texture %d of mesh %d?!", t, iter->first);
1368  }
1369  }
1370 
1371  if (globalTexture.empty())
1372  {
1373  if(mesh->tex_materials.size()==1 &&
1374  !mesh->tex_materials[0].tex_file.empty() &&
1375  uIsInteger(mesh->tex_materials[0].tex_file, false))
1376  {
1377  int textureId = uStr2Int(mesh->tex_materials[0].tex_file);
1378  SensorData data;
1379  if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
1380  {
1381  data = cachedSignatures.value(textureId).sensorData();
1382  }
1383  else if(_dbDriver)
1384  {
1385  _dbDriver->getNodeData(textureId, data, true, false, false, false);
1386  }
1387  UASSERT(!data.imageCompressed().empty());
1388  data.uncompressDataConst(&globalTexture, 0);
1389  UASSERT(!globalTexture.empty());
1390  if (_ui->checkBox_gainCompensation->isChecked() && _compensator && _compensator->getIndex(textureId) >= 0)
1391  {
1392  _compensator->apply(textureId, globalTexture, _ui->checkBox_gainRGB->isChecked());
1393  }
1394  }
1395  else
1396  {
1397  _progressDialog->appendText(tr("No textures added to mesh %1!?").arg(iter->first), Qt::darkRed);
1398  _progressDialog->setAutoClose(false);
1399  }
1400  }
1401 
1402  viewer->addCloudTextureMesh(uFormat("mesh%d",iter->first), mesh, globalTexture, iter->first>0?poses.at(iter->first):Transform::getIdentity());
1403  _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)... done.").arg(iter->first).arg(mesh->tex_polygons.size()?mesh->tex_polygons[0].size():0));
1404  QApplication::processEvents();
1405  }
1406  }
1407  else if(meshes.size())
1408  {
1409  viewer->setPolygonPicking(true);
1410  viewer->setLighting(_ui->doubleSpinBox_transferColorRadius->value() < 0.0);
1411  for(std::map<int, pcl::PolygonMesh::Ptr>::iterator iter = meshes.begin(); iter!=meshes.end(); ++iter)
1412  {
1413  _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)...").arg(iter->first).arg(iter->second->polygons.size()));
1415  bool isRGB = false;
1416  for(unsigned int i=0; i<iter->second->cloud.fields.size(); ++i)
1417  {
1418  if(iter->second->cloud.fields[i].name.compare("rgb") == 0)
1419  {
1420  isRGB=true;
1421  break;
1422  }
1423  }
1424  if(isRGB)
1425  {
1426  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
1427  pcl::fromPCLPointCloud2(iter->second->cloud, *cloud);
1428  viewer->addCloudMesh(uFormat("mesh%d",iter->first), cloud, iter->second->polygons, iter->first>0?poses.at(iter->first):Transform::getIdentity());
1429  }
1430  else
1431  {
1432  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
1433  pcl::fromPCLPointCloud2(iter->second->cloud, *cloud);
1434  viewer->addCloudMesh(uFormat("mesh%d",iter->first), cloud, iter->second->polygons, iter->first>0?poses.at(iter->first):Transform::getIdentity());
1435  }
1436  _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)... done.").arg(iter->first).arg(iter->second->polygons.size()));
1437  QApplication::processEvents();
1438  }
1439  }
1440  else if(clouds.size())
1441  {
1442  for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::iterator iter = clouds.begin(); iter!=clouds.end(); ++iter)
1443  {
1444  _progressDialog->appendText(tr("Viewing the cloud %1 (%2 points)...").arg(iter->first).arg(iter->second->size()));
1446 
1447  if(!_ui->checkBox_fromDepth->isChecked() && !_scansHaveRGB &&
1448  !(_ui->checkBox_cameraProjection->isEnabled() &&
1449  _ui->checkBox_cameraProjection->isChecked() &&
1450  _ui->checkBox_camProjRecolorPoints->isChecked() &&
1451  clouds.size()==1 && clouds.begin()->first==0))
1452  {
1453  // When laser scans are exported (and camera RGB was not applied), convert RGB to Intensity
1454  if(_ui->spinBox_normalKSearch->value()<=0 && _ui->doubleSpinBox_normalRadiusSearch->value()<=0.0)
1455  {
1456  // remove normals if not used
1457  pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIWithoutNormals(new pcl::PointCloud<pcl::PointXYZI>);
1458  cloudIWithoutNormals->resize(iter->second->size());
1459  for(unsigned int i=0; i<cloudIWithoutNormals->size(); ++i)
1460  {
1461  cloudIWithoutNormals->points[i].x = iter->second->points[i].x;
1462  cloudIWithoutNormals->points[i].y = iter->second->points[i].y;
1463  cloudIWithoutNormals->points[i].z = iter->second->points[i].z;
1464  int * intensity = (int *)&cloudIWithoutNormals->points[i].intensity;
1465  *intensity =
1466  int(iter->second->points[i].r) |
1467  int(iter->second->points[i].g) << 8 |
1468  int(iter->second->points[i].b) << 16 |
1469  int(iter->second->points[i].a) << 24;
1470  }
1471  viewer->addCloud(uFormat("cloud%d",iter->first), cloudIWithoutNormals, iter->first>0?poses.at(iter->first):Transform::getIdentity());
1472  }
1473  else
1474  {
1475  pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloudI(new pcl::PointCloud<pcl::PointXYZINormal>);
1476  cloudI->resize(iter->second->size());
1477  for(unsigned int i=0; i<cloudI->size(); ++i)
1478  {
1479  cloudI->points[i].x = iter->second->points[i].x;
1480  cloudI->points[i].y = iter->second->points[i].y;
1481  cloudI->points[i].z = iter->second->points[i].z;
1482  cloudI->points[i].normal_x = iter->second->points[i].normal_x;
1483  cloudI->points[i].normal_y = iter->second->points[i].normal_y;
1484  cloudI->points[i].normal_z = iter->second->points[i].normal_z;
1485  cloudI->points[i].curvature = iter->second->points[i].curvature;
1486  int * intensity = (int *)&cloudI->points[i].intensity;
1487  *intensity =
1488  int(iter->second->points[i].r) |
1489  int(iter->second->points[i].g) << 8 |
1490  int(iter->second->points[i].b) << 16 |
1491  int(iter->second->points[i].a) << 24;
1492  }
1493  viewer->addCloud(uFormat("cloud%d",iter->first), cloudI, iter->first>0?poses.at(iter->first):Transform::getIdentity());
1494  }
1495  }
1496  else
1497  {
1498  viewer->addCloud(uFormat("cloud%d",iter->first), iter->second, iter->first>0?poses.at(iter->first):Transform::getIdentity());
1499  }
1500 
1501  viewer->setCloudPointSize(uFormat("cloud%d",iter->first), 1);
1502  _progressDialog->appendText(tr("Viewing the cloud %1 (%2 points)... done.").arg(iter->first).arg(iter->second->size()));
1503  }
1504  }
1505  viewer->refreshView();
1506  }
1507  else
1508  {
1509  _progressDialog->setAutoClose(false);
1510  }
1512 }
1513 
1515 {
1516  int textureSize = 1024;
1517  if(_ui->comboBox_meshingTextureSize->currentIndex() > 0)
1518  {
1519  textureSize = 128 << _ui->comboBox_meshingTextureSize->currentIndex(); // start at 256
1520  }
1521  return textureSize;
1522 }
1524 {
1525  return _ui->spinBox_mesh_maxTextures->value();
1526 }
1528 {
1529  return _ui->checkBox_gainCompensation->isChecked();
1530 }
1532 {
1533  return _ui->doubleSpinBox_gainBeta->value();
1534 }
1536 {
1537  return _ui->checkBox_gainRGB->isChecked();
1538 }
1540 {
1541  return _ui->checkBox_blending->isChecked();
1542 }
1544 {
1545  int blendingDecimation = 0;
1546  if(_ui->checkBox_blending->isChecked())
1547  {
1548  if(_ui->comboBox_blendingDecimation->currentIndex() > 0)
1549  {
1550  blendingDecimation = 1 << (_ui->comboBox_blendingDecimation->currentIndex()-1);
1551  }
1552  }
1553  return blendingDecimation;
1554 }
1556 {
1557  return _ui->spinBox_textureBrightnessContrastRatioLow->value();
1558 }
1560 {
1561  return _ui->spinBox_textureBrightnessContrastRatioHigh->value();
1562 }
1564 {
1565  return _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked();
1566 }
1567 
1568 bool ExportCloudsDialog::removeDirRecursively(const QString & dirName)
1569 {
1570  bool result = true;
1571  QDir dir(dirName);
1572 
1573  if (dir.exists(dirName)) {
1574  Q_FOREACH(QFileInfo info, dir.entryInfoList(QDir::NoDotAndDotDot | QDir::System | QDir::Hidden | QDir::AllDirs | QDir::Files, QDir::DirsFirst)) {
1575  if (info.isDir()) {
1576  result = removeDirRecursively(info.absoluteFilePath());
1577  }
1578  else {
1579  result = QFile::remove(info.absoluteFilePath());
1580  }
1581 
1582  if (!result) {
1583  return result;
1584  }
1585  }
1586  result = dir.rmdir(dirName);
1587  }
1588  return result;
1589 }
1590 
1592  const std::map<int, Transform> & posesIn,
1593  const std::multimap<int, Link> & links,
1594  const std::map<int, int> & mapIds,
1595  const QMap<int, Signature> & cachedSignatures,
1596  const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
1597  const std::map<int, LaserScan> & cachedScans,
1598  const QString & workingDirectory,
1599  const ParametersMap & parameters,
1600  std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & cloudsWithNormals,
1601  std::map<int, pcl::PolygonMesh::Ptr> & meshes,
1602  std::map<int, pcl::TextureMesh::Ptr> & textureMeshes,
1603  std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels)
1604 {
1605  _canceled = false;
1606  _workingDirectory = workingDirectory;
1607  _ui->checkBox_regenerate->setEnabled(true);
1608  if(cachedSignatures.empty() && _dbDriver)
1609  {
1610  _ui->checkBox_regenerate->setChecked(true);
1611  _ui->checkBox_regenerate->setEnabled(false);
1612  }
1613  if(_compensator)
1614  {
1615  delete _compensator;
1616  _compensator = 0;
1617  }
1618  if(this->exec() == QDialog::Accepted)
1619  {
1620  std::map<int, Transform> poses = filterNodes(posesIn);
1621 
1622  if(poses.empty())
1623  {
1624  QMessageBox::critical(this, tr("Creating clouds..."), tr("Poses are empty! Cannot export/view clouds."));
1625  return false;
1626  }
1628  _progressDialog->show();
1629  int mul = 1;
1630  if(_ui->checkBox_meshing->isChecked())
1631  {
1632  mul+=1;
1633  }
1634  if(_ui->checkBox_assemble->isChecked())
1635  {
1636  mul+=1;
1637  }
1638 
1639  if(_ui->checkBox_subtraction->isChecked())
1640  {
1641  mul+=1;
1642  }
1643  if(_ui->checkBox_textureMapping->isChecked())
1644  {
1645  mul+=1;
1646  }
1647  if(_ui->checkBox_gainCompensation->isChecked())
1648  {
1649  mul+=1;
1650  }
1651  if(_ui->checkBox_mesh_quad->isEnabled()) // when enabled we are viewing the clouds
1652  {
1653  mul+=1;
1654  }
1655  _progressDialog->setMaximumSteps(int(poses.size())*mul+1);
1656 
1657  bool loadClouds = true;
1658 #ifdef RTABMAP_OPENCHISEL
1659  if(_ui->comboBox_meshingApproach->currentIndex()==4 && _ui->checkBox_assemble->isChecked())
1660  {
1661  loadClouds = !_ui->checkBox_fromDepth->isChecked();
1662  }
1663 #endif
1664 
1665  bool has2dScans = false;
1666  std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
1667  if(loadClouds)
1668  {
1669  clouds = this->getClouds(
1670  poses,
1671  cachedSignatures,
1672  cachedClouds,
1673  cachedScans,
1674  parameters,
1675  has2dScans,
1676  _scansHaveRGB);
1677  }
1678  else
1679  {
1680  // just create empty clouds
1681  for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
1682  {
1683  clouds.insert(std::make_pair(iter->first,
1684  std::make_pair(
1685  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr(new pcl::PointCloud<pcl::PointXYZRGBNormal>),
1686  pcl::IndicesPtr(new std::vector<int>))));
1687 
1688  }
1689  }
1690 
1691  std::set<int> validCameras = uKeysSet(clouds);
1692 
1693  UDEBUG("");
1694  if(_canceled)
1695  {
1696  return false;
1697  }
1698 
1699  if(clouds.empty())
1700  {
1701  _progressDialog->setAutoClose(false);
1702  if(_ui->checkBox_regenerate->isEnabled() && !_ui->checkBox_regenerate->isChecked())
1703  {
1704  QMessageBox::warning(this, tr("Creating clouds..."), tr("Could create clouds for %1 node(s). You "
1705  "may want to activate clouds regeneration option.").arg(poses.size()));
1706  }
1707  else
1708  {
1709  QMessageBox::warning(this, tr("Creating clouds..."), tr("Could not create clouds for %1 "
1710  "node(s). The cache may not contain point cloud data. Try re-downloading the map.").arg(poses.size()));
1711  }
1712  return false;
1713  }
1714 
1715  UDEBUG("");
1716  if(_ui->checkBox_gainCompensation->isChecked() && _ui->checkBox_fromDepth->isChecked() && clouds.size() > 1 &&
1717  // Do compensation later if we are merging textures on a dense assembled cloud
1718  !(_ui->checkBox_meshing->isChecked() &&
1719  _ui->checkBox_textureMapping->isEnabled() &&
1720  _ui->checkBox_textureMapping->isChecked() &&
1721  _ui->comboBox_pipeline->currentIndex()==1 &&
1722  _ui->checkBox_assemble->isChecked() &&
1723  _ui->comboBox_meshingTextureSize->isEnabled() &&
1724  _ui->comboBox_meshingTextureSize->currentIndex() > 0) &&
1725  // Don't do compensation if clouds are in camera frame
1726  !(_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex()==2))
1727  {
1728  UASSERT(_compensator == 0);
1729  _compensator = new GainCompensator(_ui->doubleSpinBox_gainRadius->value(), _ui->doubleSpinBox_gainOverlap->value(), 0.01, _ui->doubleSpinBox_gainBeta->value());
1730 
1731  if(_ui->checkBox_gainFull->isChecked())
1732  {
1733  _progressDialog->appendText(tr("Full gain compensation of %1 clouds...").arg(clouds.size()));
1734  }
1735  else
1736  {
1737  _progressDialog->appendText(tr("Gain compensation of %1 clouds...").arg(clouds.size()));
1738  }
1739  QApplication::processEvents();
1740  uSleep(100);
1741  QApplication::processEvents();
1742 
1743  if(_ui->checkBox_gainFull->isChecked())
1744  {
1745  std::multimap<int, Link> allLinks;
1746  for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator iter=clouds.begin(); iter!=clouds.end(); ++iter)
1747  {
1748  int from = iter->first;
1749  std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator jter = iter;
1750  ++jter;
1751  for(;jter!=clouds.end(); ++jter)
1752  {
1753  int to = jter->first;
1754  allLinks.insert(std::make_pair(from, Link(from, to, Link::kUserClosure, poses.at(from).inverse()*poses.at(to))));
1755  }
1756  }
1757 
1758  _compensator->feed(clouds, allLinks);
1759  }
1760  else
1761  {
1762  _compensator->feed(clouds, links);
1763  }
1764 
1765  if(!(_ui->checkBox_meshing->isChecked() &&
1766  _ui->checkBox_textureMapping->isEnabled() &&
1767  _ui->checkBox_textureMapping->isChecked()))
1768  {
1769  _progressDialog->appendText(tr("Applying gain compensation..."));
1770  for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator jter=clouds.begin();jter!=clouds.end(); ++jter)
1771  {
1772  if(jter!=clouds.end())
1773  {
1774  double gain = _compensator->getGain(jter->first);;
1775  _compensator->apply(jter->first, jter->second.first, jter->second.second, _ui->checkBox_gainRGB->isChecked());
1776 
1777  _progressDialog->appendText(tr("Cloud %1 has gain %2").arg(jter->first).arg(gain));
1779  QApplication::processEvents();
1780  if(_canceled)
1781  {
1782  return false;
1783  }
1784  }
1785  }
1786  }
1787  }
1788 
1789  UDEBUG("");
1790  std::map<int, Transform> normalViewpoints = poses;
1791  if(_ui->checkBox_assemble->isChecked())
1792  {
1793  // Adjust view points with local transforms
1794  for(std::map<int, Transform>::iterator iter= normalViewpoints.begin(); iter!=normalViewpoints.end(); ++iter)
1795  {
1796  if(_ui->checkBox_fromDepth->isChecked())
1797  {
1798  std::vector<CameraModel> models;
1799  std::vector<StereoCameraModel> stereoModels;
1800  if(cachedSignatures.contains(iter->first))
1801  {
1802  const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
1803  models = data.cameraModels();
1804  stereoModels = data.stereoCameraModels();
1805  }
1806  else if(_dbDriver)
1807  {
1808  _dbDriver->getCalibration(iter->first, models, stereoModels);
1809  }
1810 
1811  if(models.size() && !models[0].localTransform().isNull())
1812  {
1813  iter->second *= models[0].localTransform();
1814  }
1815  else if(stereoModels.size() && !stereoModels[0].localTransform().isNull())
1816  {
1817  iter->second *= stereoModels[0].localTransform();
1818  }
1819  }
1820  else
1821  {
1822  if(uContains(cachedScans, iter->first))
1823  {
1824  iter->second *= cachedScans.at(iter->first).localTransform();
1825  }
1826  else if(cachedSignatures.contains(iter->first))
1827  {
1828  const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
1829  if(!data.laserScanCompressed().isEmpty())
1830  {
1831  iter->second *= data.laserScanCompressed().localTransform();
1832  }
1833  else if(!data.laserScanRaw().isEmpty())
1834  {
1835  iter->second *= data.laserScanRaw().localTransform();
1836  }
1837  }
1838  else if(_dbDriver)
1839  {
1840  LaserScan scan;
1841  _dbDriver->getLaserScanInfo(iter->first, scan);
1842  iter->second *= scan.localTransform();
1843  }
1844  }
1845  }
1846  }
1847 
1848  UDEBUG("");
1849  pcl::PointCloud<pcl::PointXYZ>::Ptr rawAssembledCloud(new pcl::PointCloud<pcl::PointXYZ>);
1850  std::vector<int> rawCameraIndices;
1851  if(_ui->checkBox_assemble->isChecked() &&
1852  !((_ui->comboBox_pipeline->currentIndex()==0 || _ui->comboBox_meshingApproach->currentIndex()==4) && _ui->checkBox_meshing->isChecked()))
1853  {
1854  _progressDialog->appendText(tr("Assembling %1 clouds...").arg(clouds.size()));
1855  QApplication::processEvents();
1856 
1857  int i =0;
1858  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr assembledCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1859  for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator iter=clouds.begin();
1860  iter!= clouds.end();
1861  ++iter)
1862  {
1863  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformed(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1864  if(iter->second.first->isOrganized())
1865  {
1866  pcl::copyPointCloud(*iter->second.first, *iter->second.second, *transformed);
1867  transformed = util3d::transformPointCloud(transformed, poses.at(iter->first));
1868  }
1869  else
1870  {
1871  // it looks like that using only transformPointCloud with indices
1872  // flushes the colors, so we should extract points before... maybe a too old PCL version
1873  pcl::copyPointCloud(*iter->second.first, *iter->second.second, *transformed);
1874  transformed = rtabmap::util3d::transformPointCloud(transformed, poses.at(iter->first));
1875  }
1876 
1877  *assembledCloud += *transformed;
1878  rawCameraIndices.resize(assembledCloud->size(), iter->first);
1879 
1880  _progressDialog->appendText(tr("Assembled cloud %1, total=%2 (%3/%4).").arg(iter->first).arg(assembledCloud->size()).arg(++i).arg(clouds.size()));
1882  QApplication::processEvents();
1883  if(_canceled)
1884  {
1885  return false;
1886  }
1887  }
1888 
1889  assembledCloud->is_dense = true;
1890  if(_ui->spinBox_normalKSearch->value()>0 || _ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
1891  {
1892  pcl::copyPointCloud(*assembledCloud, *rawAssembledCloud);
1893  }
1894 
1895  if(_ui->doubleSpinBox_voxelSize_assembled->value())
1896  {
1897  _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...")
1898  .arg(assembledCloud->size())
1899  .arg(_ui->doubleSpinBox_voxelSize_assembled->value()));
1900  QApplication::processEvents();
1901  unsigned int before = assembledCloud->size();
1902  assembledCloud = util3d::voxelize(
1903  assembledCloud,
1904  _ui->doubleSpinBox_voxelSize_assembled->value());
1905  _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...done! (%3 points)")
1906  .arg(before)
1907  .arg(_ui->doubleSpinBox_voxelSize_assembled->value())
1908  .arg(assembledCloud->size()));
1909  }
1910 
1911  clouds.clear();
1912  pcl::IndicesPtr indices(new std::vector<int>);
1913  indices->resize(assembledCloud->size());
1914  for(unsigned int i=0; i<indices->size(); ++i)
1915  {
1916  indices->at(i) = i;
1917  }
1918 
1919  if(!_ui->checkBox_fromDepth->isChecked() && !has2dScans &&
1920  (_ui->spinBox_normalKSearch->value()>0 || _ui->doubleSpinBox_normalRadiusSearch->value()>0.0))
1921  {
1922  _progressDialog->appendText(tr("Computing normals (%1 points, K=%2, radius=%3 m)...")
1923  .arg(assembledCloud->size())
1924  .arg(_ui->spinBox_normalKSearch->value())
1925  .arg(_ui->doubleSpinBox_normalRadiusSearch->value()));
1926 
1927  // recompute normals
1928  pcl::PointCloud<pcl::PointXYZ>::Ptr cloudWithoutNormals(new pcl::PointCloud<pcl::PointXYZ>);
1929  pcl::copyPointCloud(*assembledCloud, *cloudWithoutNormals);
1930  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value());
1931 
1932  UASSERT(assembledCloud->size() == normals->size());
1933  for(unsigned int i=0; i<normals->size(); ++i)
1934  {
1935  assembledCloud->points[i].normal_x = normals->points[i].normal_x;
1936  assembledCloud->points[i].normal_y = normals->points[i].normal_y;
1937  assembledCloud->points[i].normal_z = normals->points[i].normal_z;
1938  }
1939  _progressDialog->appendText(tr("Adjusting normals to viewpoints (%1 points)...").arg(assembledCloud->size()));
1940 
1941  // adjust with point of views
1943  normalViewpoints,
1944  rawAssembledCloud,
1945  rawCameraIndices,
1946  assembledCloud,
1947  _ui->doubleSpinBox_groundNormalsUp->value());
1948  }
1949 
1950  if(_ui->spinBox_randomSamples_assembled->value()>0 &&
1951  (int)assembledCloud->size() > _ui->spinBox_randomSamples_assembled->value())
1952  {
1953  _progressDialog->appendText(tr("Random samples filtering (in=%1 points, samples=%2)...")
1954  .arg(assembledCloud->size())
1955  .arg(_ui->spinBox_randomSamples_assembled->value()));
1956  assembledCloud = util3d::randomSampling(assembledCloud, _ui->spinBox_randomSamples_assembled->value());
1957  _progressDialog->appendText(tr("Random samples filtering (out=%1 points, samples=%2)... done!")
1958  .arg(assembledCloud->size())
1959  .arg(_ui->spinBox_randomSamples_assembled->value()));
1960  }
1961 
1962  clouds.insert(std::make_pair(0, std::make_pair(assembledCloud, indices)));
1963  }
1964 
1965  UDEBUG("");
1966  if(_canceled)
1967  {
1968  return false;
1969  }
1970 
1971  if(_ui->checkBox_smoothing->isEnabled() && _ui->checkBox_smoothing->isChecked() && !has2dScans)
1972  {
1973  _progressDialog->appendText(tr("Smoothing the surface using Moving Least Squares (MLS) algorithm... "
1974  "[search radius=%1m voxel=%2m]").arg(_ui->doubleSpinBox_mlsRadius->value()).arg(_ui->doubleSpinBox_voxelSize_assembled->value()));
1975  QApplication::processEvents();
1976  uSleep(100);
1977  QApplication::processEvents();
1978  }
1979 
1980  //fill cloudWithNormals
1981  for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator iter=clouds.begin();
1982  iter!= clouds.end();)
1983  {
1984  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudWithNormals = iter->second.first;
1985 
1986  if(_ui->checkBox_smoothing->isEnabled() && _ui->checkBox_smoothing->isChecked() && !has2dScans)
1987  {
1988  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals(new pcl::PointCloud<pcl::PointXYZRGB>);
1989  if(iter->second.second->size())
1990  {
1991  pcl::copyPointCloud(*cloudWithNormals, *iter->second.second, *cloudWithoutNormals);
1992  }
1993  else
1994  {
1995  pcl::copyPointCloud(*cloudWithNormals, *cloudWithoutNormals);
1996  }
1997 
1998  _progressDialog->appendText(tr("Smoothing (MLS) the cloud (%1 points)...").arg(cloudWithNormals->size()));
1999  QApplication::processEvents();
2000  uSleep(100);
2001  QApplication::processEvents();
2002  if(_canceled)
2003  {
2004  return false;
2005  }
2006 
2007  cloudWithNormals = util3d::mls(
2008  cloudWithoutNormals,
2009  (float)_ui->doubleSpinBox_mlsRadius->value(),
2010  _ui->spinBox_polygonialOrder->value(),
2011  _ui->comboBox_upsamplingMethod->currentIndex(),
2012  (float)_ui->doubleSpinBox_sampleRadius->value(),
2013  (float)_ui->doubleSpinBox_sampleStep->value(),
2014  _ui->spinBox_randomPoints->value(),
2015  (float)_ui->doubleSpinBox_dilationVoxelSize->value(),
2016  _ui->spinBox_dilationSteps->value());
2017 
2018  // make sure there are no nans
2019  UDEBUG("NaNs filtering... size before = %d", cloudWithNormals->size());
2020  cloudWithNormals = util3d::removeNaNNormalsFromPointCloud(cloudWithNormals);
2021  UDEBUG("NaNs filtering... size after = %d", cloudWithNormals->size());
2022 
2023  if(_ui->checkBox_assemble->isChecked())
2024  {
2025  // Re-voxelize to make sure to have uniform density
2026  if(_ui->doubleSpinBox_mls_outputVoxelSize->value())
2027  {
2028  _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...")
2029  .arg(cloudWithNormals->size())
2030  .arg(_ui->doubleSpinBox_mls_outputVoxelSize->value()));
2031  QApplication::processEvents();
2032 
2033  cloudWithNormals = util3d::voxelize(
2034  cloudWithNormals,
2035  _ui->doubleSpinBox_mls_outputVoxelSize->value());
2036  }
2037 
2038  _progressDialog->appendText(tr("Update %1 normals with %2 camera views...").arg(cloudWithNormals->size()).arg(poses.size()));
2039 
2041  normalViewpoints,
2042  rawAssembledCloud,
2043  rawCameraIndices,
2044  cloudWithNormals);
2045  }
2046  }
2047  else if(iter->second.first->isOrganized() && _ui->checkBox_filtering->isChecked())
2048  {
2049  cloudWithNormals = util3d::extractIndices(iter->second.first, iter->second.second, false, true);
2050  }
2051 
2052  cloudsWithNormals.insert(std::make_pair(iter->first, cloudWithNormals));
2053 
2054  // clear memory
2055  clouds.erase(iter++);
2056 
2058  QApplication::processEvents();
2059  if(_canceled)
2060  {
2061  return false;
2062  }
2063  }
2064 
2065  UDEBUG("");
2066 #ifdef RTABMAP_CPUTSDF
2067  cpu_tsdf::TSDFVolumeOctree::Ptr tsdf;
2068 #endif
2069 #ifdef RTABMAP_OPENCHISEL
2070  chisel::ChiselPtr chiselMap;
2071  chisel::ProjectionIntegrator projectionIntegrator;
2072 #endif
2073 
2074  //used for organized texturing below
2075  std::map<int, std::vector<int> > organizedIndices;
2076  std::map<int, cv::Size> organizedCloudSizes;
2077 
2078  //mesh
2079  UDEBUG("Meshing=%d", _ui->checkBox_meshing->isChecked()?1:0);
2080  if(_ui->checkBox_meshing->isChecked() && !has2dScans)
2081  {
2082 
2083 #ifdef RTABMAP_OPENCHISEL
2084  if(_ui->comboBox_meshingApproach->currentIndex()==4 && _ui->checkBox_assemble->isChecked())
2085  {
2086  _progressDialog->appendText(tr("Creating TSDF volume with OpenChisel... "));
2087 
2088  QApplication::processEvents();
2089  uSleep(100);
2090  QApplication::processEvents();
2091 
2092  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2093  std::vector<pcl::Vertices> mergedPolygons;
2094 
2095  int cloudsAdded = 1;
2096  for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::iterator iter=cloudsWithNormals.begin();
2097  iter!= cloudsWithNormals.end();
2098  ++iter,++cloudsAdded)
2099  {
2100  std::vector<CameraModel> models;
2101  StereoCameraModel stereoModel;
2102  bool cacheHasCompressedImage = false;
2103  LaserScan scanInfo;
2104  if(cachedSignatures.contains(iter->first))
2105  {
2106  const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
2107  models = data.cameraModels();
2108  cacheHasCompressedImage = !data.imageCompressed().empty();
2109  scanInfo = !data.laserScanRaw().isEmpty()?data.laserScanRaw():data.laserScanCompressed();
2110  }
2111  else if(_dbDriver)
2112  {
2113  _dbDriver->getCalibration(iter->first, models, stereoModel);
2114  _dbDriver->getLaserScanInfo(iter->first, scanInfo);
2115  }
2116 
2117  if(chiselMap.get() == 0)
2118  {
2119  UDEBUG("");
2120  int chunkSizeX = _ui->spinBox_openchisel_chunk_size_x->value();
2121  int chunkSizeY = _ui->spinBox_openchisel_chunk_size_y->value();
2122  int chunkSizeZ = _ui->spinBox_openchisel_chunk_size_z->value();
2123  float voxelResolution = _ui->doubleSpinBox_voxelSize_assembled->value();
2124  if(voxelResolution <=0.0f)
2125  {
2126  _progressDialog->appendText(tr("OpenChisel: Voxel size should not be null!"), Qt::darkYellow);
2127  _progressDialog->setAutoClose(false);
2128  break;
2129  }
2130  bool useColor = _ui->checkBox_fromDepth->isChecked();
2131  chiselMap.reset(new chisel::Chisel(Eigen::Vector3i(chunkSizeX, chunkSizeY, chunkSizeZ), voxelResolution, useColor));
2132  double truncationDistConst = _ui->doubleSpinBox_openchisel_truncation_constant->value();
2133  double truncationDistLinear = _ui->doubleSpinBox_openchisel_truncation_linear->value();
2134  double truncationDistQuad = _ui->doubleSpinBox_openchisel_truncation_quadratic->value();
2135  double truncationDistScale = _ui->doubleSpinBox_openchisel_truncation_scale->value();
2136  int weight = _ui->spinBox_openchisel_integration_weight->value();
2137  bool useCarving = _ui->checkBox_openchisel_use_voxel_carving->isChecked();
2138  double carvingDist = _ui->doubleSpinBox_openchisel_carving_dist_m->value();
2139  chisel::Vec4 truncation(truncationDistQuad, truncationDistLinear, truncationDistConst, truncationDistScale);
2140  UDEBUG("If crashing just after this message, make sure PCL and OpenChisel are built both with -march=native or both without -march=native");
2141  projectionIntegrator.SetCentroids(chiselMap->GetChunkManager().GetCentroids());
2142  projectionIntegrator.SetTruncator(chisel::TruncatorPtr(new chisel::QuadraticTruncator(truncation(0), truncation(1), truncation(2), truncation(3))));
2143  projectionIntegrator.SetWeighter(chisel::WeighterPtr(new chisel::ConstantWeighter(weight)));
2144  projectionIntegrator.SetCarvingDist(carvingDist);
2145  projectionIntegrator.SetCarvingEnabled(useCarving);
2146  }
2147 
2148  UDEBUG("");
2149  double nearPlaneDist = _ui->doubleSpinBox_openchisel_near_plane_dist->value();
2150  double farPlaneDist = _ui->doubleSpinBox_openchisel_far_plane_dist->value();
2151  if(_ui->checkBox_fromDepth->isChecked())
2152  {
2153  if(models.size() == 1 && !models[0].localTransform().isNull())
2154  {
2155  // get just the depth
2156  cv::Mat rgb;
2157  cv::Mat depth;
2158  if(cacheHasCompressedImage)
2159  {
2160  cachedSignatures.find(iter->first)->sensorData().uncompressDataConst(&rgb, &depth);
2161  }
2162  else if(_dbDriver)
2163  {
2164  SensorData data;
2165  _dbDriver->getNodeData(iter->first, data, true, false, false, false);
2166  data.uncompressDataConst(&rgb, &depth);
2167  }
2168  if(!rgb.empty() && !depth.empty())
2169  {
2170  CameraModel rgbModel = models[0];
2171  CameraModel depthModel = rgbModel;
2172  if(rgb.cols > depth.cols)
2173  {
2174  UASSERT(rgb.cols % depth.cols == 0);
2175  depthModel = depthModel.scaled(double(depth.cols)/double(rgb.cols));
2176  }
2177 
2178  if(depth.type() == CV_16UC1)
2179  {
2180  depth = util2d::cvtDepthToFloat(depth);
2181  }
2182 
2183  std::shared_ptr<chisel::ColorImage<unsigned char> > colorChisel = colorImageToChisel(rgb);
2184  std::shared_ptr<chisel::DepthImage<float> > depthChisel = depthImageToChisel(depth);
2185 
2186  chisel::PinholeCamera cameraColor = cameraModelToChiselCamera(rgbModel);
2187  chisel::PinholeCamera cameraDepth = cameraModelToChiselCamera(depthModel);
2188  cameraColor.SetNearPlane(nearPlaneDist);
2189  cameraColor.SetFarPlane(farPlaneDist);
2190  cameraDepth.SetNearPlane(nearPlaneDist);
2191  cameraDepth.SetFarPlane(farPlaneDist);
2192 
2193  chisel::Transform pose_rel_to_first_frame = (poses.at(iter->first)*models[0].localTransform()).toEigen3f();
2194  chiselMap->IntegrateDepthScanColor<float, unsigned char>(projectionIntegrator, depthChisel, pose_rel_to_first_frame, cameraDepth, colorChisel, pose_rel_to_first_frame, cameraColor);
2195  UDEBUG("");
2196  }
2197  else
2198  {
2199  _progressDialog->appendText(tr("OpenChisel: Depth and RGB images not found for %1!").arg(iter->first), Qt::darkYellow);
2200  }
2201  }
2202  else
2203  {
2204  _progressDialog->appendText(tr("OpenChisel: Invalid camera model for cloud %1! Only single RGB-D camera supported.").arg(iter->first), Qt::darkYellow);
2205  _progressDialog->setAutoClose(false);
2206  break;
2207  }
2208  }
2209  else if(!scanInfo.localTransform().isNull())
2210  {
2211  chisel::PointCloudPtr chiselCloud = pointCloudRGBToChisel(*iter->second, scanInfo.localTransform().inverse());
2212  chisel::Transform pose_rel_to_first_frame = (poses.at(iter->first)*scanInfo.localTransform()).toEigen3f();
2213  chiselMap->IntegratePointCloud(projectionIntegrator, *chiselCloud, pose_rel_to_first_frame, farPlaneDist);
2214  UDEBUG("");
2215  }
2216  else
2217  {
2218  _progressDialog->appendText(tr("OpenChisel: not valid scan info for cloud %1!").arg(iter->first), Qt::darkYellow);
2219  _progressDialog->setAutoClose(false);
2220  break;
2221  }
2222  chiselMap->UpdateMeshes();
2223  UDEBUG("");
2224  _progressDialog->appendText(tr("OpenChisel: Integrated cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2225 
2227  QApplication::processEvents();
2228  if(_canceled)
2229  {
2230  return false;
2231  }
2232  }
2233  }
2234  else
2235 #endif
2236 
2237  if(_ui->comboBox_pipeline->currentIndex() == 0)
2238  {
2239  if(_ui->comboBox_meshingApproach->currentIndex()==2)
2240  {
2241  _progressDialog->appendText(tr("Creating TSDF volume with CPUTSDF... "));
2242  }
2243  else
2244  {
2245  _progressDialog->appendText(tr("Organized fast mesh... "));
2246  }
2247  QApplication::processEvents();
2248  uSleep(100);
2249  QApplication::processEvents();
2250 
2251  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2252  std::vector<pcl::Vertices> mergedPolygons;
2253 
2254  int cloudsAdded = 1;
2255  for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::iterator iter=cloudsWithNormals.begin();
2256  iter!= cloudsWithNormals.end();
2257  ++iter,++cloudsAdded)
2258  {
2259  if(iter->second->isOrganized())
2260  {
2261  if(iter->second->size())
2262  {
2263  Eigen::Vector3f viewpoint(0.0f,0.0f,0.0f);
2264 
2265  std::vector<CameraModel> models;
2266  std::vector<StereoCameraModel> stereoModels;
2267  if(cachedSignatures.contains(iter->first))
2268  {
2269  const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
2270  models = data.cameraModels();
2271  stereoModels = data.stereoCameraModels();
2272  }
2273  else if(_dbDriver)
2274  {
2275  _dbDriver->getCalibration(iter->first, models, stereoModels);
2276  }
2277 
2278 #ifdef RTABMAP_CPUTSDF
2279  if(_ui->comboBox_meshingApproach->currentIndex()==2 && _ui->checkBox_assemble->isChecked())
2280  {
2281  if(tsdf.get() == 0)
2282  {
2283  if(models.size()==1 && models[0].isValidForProjection() && models[0].imageHeight()>0 && models[0].imageWidth()>0)
2284  {
2285  float tsdf_size = _ui->doubleSpinBox_cputsdf_size->value();
2286  float cell_size = _ui->doubleSpinBox_cputsdf_resolution->value();
2287  int num_random_splits = _ui->spinBox_cputsdf_randomSplit->value();
2288  int tsdf_res;
2289  int desired_res = tsdf_size / cell_size;
2290  // Snap to nearest power of 2;
2291  int n = 1;
2292  while (desired_res > n)
2293  {
2294  n *= 2;
2295  }
2296  tsdf_res = n;
2297  _progressDialog->appendText(tr("CPU-TSDF: Setting resolution: %1 with grid size %2").arg(tsdf_res).arg(tsdf_size));
2298  tsdf.reset (new cpu_tsdf::TSDFVolumeOctree);
2299  tsdf->setGridSize (tsdf_size, tsdf_size, tsdf_size);
2300  tsdf->setResolution (tsdf_res, tsdf_res, tsdf_res);
2301  float decimation = float(models[0].imageWidth()) / float(iter->second->width);
2302  tsdf->setImageSize (models[0].imageWidth()/decimation, models[0].imageHeight()/decimation);
2303  tsdf->setCameraIntrinsics (models[0].fx()/decimation, models[0].fy()/decimation, models[0].cx()/decimation, models[0].cy()/decimation);
2304  tsdf->setNumRandomSplts (num_random_splits);
2305  tsdf->setSensorDistanceBounds (0, 9999);
2306  tsdf->setIntegrateColor(true);
2307  tsdf->setDepthTruncationLimits (_ui->doubleSpinBox_cputsdf_tuncPos->value(), _ui->doubleSpinBox_cputsdf_tuncNeg->value());
2308  tsdf->reset ();
2309  }
2310  else
2311  {
2312  _progressDialog->appendText(tr("CPU-TSDF: Invalid camera model! Only single RGB-D camera supported."), Qt::darkYellow);
2313  _progressDialog->setAutoClose(false);
2314  break;
2315  }
2316  }
2317 
2318  if(tsdf.get())
2319  {
2320  if(tsdf.get() && models.size() == 1 && !models[0].localTransform().isNull())
2321  {
2322  Eigen::Affine3d pose_rel_to_first_frame = ((poses.begin()->second.inverse() * poses.at(iter->first))*models[0].localTransform()).toEigen3d();
2323  if(!tsdf->integrateCloud(*util3d::transformPointCloud(iter->second, models[0].localTransform().inverse()), pcl::PointCloud<pcl::Normal>(), pose_rel_to_first_frame))
2324  {
2325  _progressDialog->appendText(tr("CPU-TSDF: Failed integrating cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2326  }
2327  else
2328  {
2329  _progressDialog->appendText(tr("CPU-TSDF: Integrated cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2330  }
2331  }
2332  }
2333  }
2334  else
2335 #endif
2336  {
2337  if((_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex() != 2) ||
2338  !iter->second->isOrganized())
2339  {
2340  if(models.size() && !models[0].localTransform().isNull())
2341  {
2342  viewpoint[0] = models[0].localTransform().x();
2343  viewpoint[1] = models[0].localTransform().y();
2344  viewpoint[2] = models[0].localTransform().z();
2345  }
2346  else if(stereoModels.size() && !stereoModels[0].localTransform().isNull())
2347  {
2348  viewpoint[0] = stereoModels[0].localTransform().x();
2349  viewpoint[1] = stereoModels[0].localTransform().y();
2350  viewpoint[2] = stereoModels[0].localTransform().z();
2351  }
2352  }
2353 
2354  std::vector<pcl::Vertices> polygons = util3d::organizedFastMesh(
2355  iter->second,
2356  _ui->doubleSpinBox_mesh_angleTolerance->value()*M_PI/180.0,
2357  _ui->checkBox_mesh_quad->isEnabled() && _ui->checkBox_mesh_quad->isChecked(),
2358  _ui->spinBox_mesh_triangleSize->value(),
2359  viewpoint);
2360 
2361  if(_ui->spinBox_mesh_minClusterSize->value() != 0)
2362  {
2363  _progressDialog->appendText(tr("Filter small polygon clusters..."));
2364  QApplication::processEvents();
2365 
2366  // filter polygons
2367  std::vector<std::set<int> > neighbors;
2368  std::vector<std::set<int> > vertexToPolygons;
2370  (int)iter->second->size(),
2371  neighbors,
2372  vertexToPolygons);
2373  std::list<std::list<int> > clusters = util3d::clusterPolygons(
2374  neighbors,
2375  _ui->spinBox_mesh_minClusterSize->value()<0?0:_ui->spinBox_mesh_minClusterSize->value());
2376 
2377  std::vector<pcl::Vertices> filteredPolygons(polygons.size());
2378  if(_ui->spinBox_mesh_minClusterSize->value() < 0)
2379  {
2380  // only keep the biggest cluster
2381  std::list<std::list<int> >::iterator biggestClusterIndex = clusters.end();
2382  unsigned int biggestClusterSize = 0;
2383  for(std::list<std::list<int> >::iterator iter=clusters.begin(); iter!=clusters.end(); ++iter)
2384  {
2385  if(iter->size() > biggestClusterSize)
2386  {
2387  biggestClusterIndex = iter;
2388  biggestClusterSize = iter->size();
2389  }
2390  }
2391  if(biggestClusterIndex != clusters.end())
2392  {
2393  int oi=0;
2394  for(std::list<int>::iterator jter=biggestClusterIndex->begin(); jter!=biggestClusterIndex->end(); ++jter)
2395  {
2396  filteredPolygons[oi++] = polygons.at(*jter);
2397  }
2398  filteredPolygons.resize(oi);
2399  }
2400  }
2401  else
2402  {
2403  int oi=0;
2404  for(std::list<std::list<int> >::iterator iter=clusters.begin(); iter!=clusters.end(); ++iter)
2405  {
2406  for(std::list<int>::iterator jter=iter->begin(); jter!=iter->end(); ++jter)
2407  {
2408  filteredPolygons[oi++] = polygons.at(*jter);
2409  }
2410  }
2411  filteredPolygons.resize(oi);
2412  }
2413  int before = (int)polygons.size();
2414  polygons = filteredPolygons;
2415 
2416  if(polygons.size() == 0)
2417  {
2418  std::string msg = uFormat("All %d polygons filtered after polygon cluster filtering. Cluster minimum size is %d.", before, _ui->spinBox_mesh_minClusterSize->value());
2419  _progressDialog->appendText(msg.c_str(), Qt::darkYellow);
2420  UWARN(msg.c_str());
2421  }
2422 
2423  _progressDialog->appendText(tr("Filtered %1 polygons.").arg(before-(int)polygons.size()));
2424  QApplication::processEvents();
2425  }
2426 
2427  _progressDialog->appendText(tr("Mesh %1 created with %2 polygons (%3/%4).").arg(iter->first).arg(polygons.size()).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2428 
2429  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr denseCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2430  std::vector<pcl::Vertices> densePolygons;
2431  std::vector<int> denseToOrganizedIndices = util3d::filterNotUsedVerticesFromMesh(*iter->second, polygons, *denseCloud, densePolygons);
2432 
2433  if(!_ui->checkBox_assemble->isChecked() ||
2434  (_ui->checkBox_textureMapping->isEnabled() &&
2435  _ui->checkBox_textureMapping->isChecked() &&
2436  _ui->doubleSpinBox_voxelSize_assembled->value() == 0.0)) // don't assemble now if we are texturing
2437  {
2438  if(_ui->checkBox_assemble->isChecked())
2439  {
2440  denseCloud = util3d::transformPointCloud(denseCloud, poses.at(iter->first));
2441  }
2442 
2443  pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
2444  pcl::toPCLPointCloud2(*denseCloud, mesh->cloud);
2445  mesh->polygons = densePolygons;
2446 
2447  organizedIndices.insert(std::make_pair(iter->first, denseToOrganizedIndices));
2448  organizedCloudSizes.insert(std::make_pair(iter->first, cv::Size(iter->second->width, iter->second->height)));
2449 
2450  meshes.insert(std::make_pair(iter->first, mesh));
2451  }
2452  else
2453  {
2454  denseCloud = util3d::transformPointCloud(denseCloud, poses.at(iter->first));
2455  if(mergedClouds->size() == 0)
2456  {
2457  *mergedClouds = *denseCloud;
2458  mergedPolygons = densePolygons;
2459  }
2460  else
2461  {
2462  util3d::appendMesh(*mergedClouds, mergedPolygons, *denseCloud, densePolygons);
2463  }
2464  }
2465  }
2466  }
2467  else
2468  {
2469  _progressDialog->appendText(tr("Mesh %1 not created (no valid points) (%2/%3).").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2470  }
2471  }
2472  else
2473  {
2474  int weight = 0;
2475  if(cachedSignatures.contains(iter->first))
2476  {
2477  const Signature & s = cachedSignatures.find(iter->first).value();
2478  weight = s.getWeight();
2479  }
2480  else if(_dbDriver)
2481  {
2482  _dbDriver->getWeight(iter->first, weight);
2483  }
2484  if(weight>=0) // don't show error for intermediate nodes
2485  {
2486  _progressDialog->appendText(tr("Mesh %1 not created (cloud is not organized). You may want to check cloud regeneration option (%2/%3).").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2487  }
2488  }
2489 
2491  QApplication::processEvents();
2492  if(_canceled)
2493  {
2494  return false;
2495  }
2496  }
2497 
2498  if(_ui->checkBox_assemble->isChecked() && mergedClouds->size())
2499  {
2500  if(_ui->doubleSpinBox_voxelSize_assembled->value())
2501  {
2502  _progressDialog->appendText(tr("Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").arg(mergedClouds->size()).arg(mergedPolygons.size()));
2503  QApplication::processEvents();
2504 
2505  mergedPolygons = util3d::filterCloseVerticesFromMesh(
2506  mergedClouds,
2507  mergedPolygons,
2508  _ui->doubleSpinBox_voxelSize_assembled->value(),
2509  M_PI/4,
2510  true);
2511 
2512  // filter invalid polygons
2513  unsigned int count = mergedPolygons.size();
2514  mergedPolygons = util3d::filterInvalidPolygons(mergedPolygons);
2515  _progressDialog->appendText(tr("Filtered %1 invalid polygons.").arg(count-mergedPolygons.size()));
2516  QApplication::processEvents();
2517 
2518  // filter not used vertices
2519  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2520  std::vector<pcl::Vertices> filteredPolygons;
2521  util3d::filterNotUsedVerticesFromMesh(*mergedClouds, mergedPolygons, *filteredCloud, filteredPolygons);
2522  mergedClouds = filteredCloud;
2523  mergedPolygons = filteredPolygons;
2524  }
2525 
2526  pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
2527  pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
2528  mesh->polygons = mergedPolygons;
2529 
2530  meshes.insert(std::make_pair(0, mesh));
2531 
2533  QApplication::processEvents();
2534  }
2535  }
2536  else // dense pipeline
2537  {
2538  if(_ui->comboBox_meshingApproach->currentIndex() == 0)
2539  {
2540  _progressDialog->appendText(tr("Greedy projection triangulation... [radius=%1m]").arg(_ui->doubleSpinBox_gp3Radius->value()));
2541  }
2542  else
2543  {
2544  _progressDialog->appendText(tr("Poisson surface reconstruction..."));
2545  }
2546  QApplication::processEvents();
2547  uSleep(100);
2548  QApplication::processEvents();
2549 
2550  int cloudsAdded=1;
2551  for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::iterator iter=cloudsWithNormals.begin();
2552  iter!= cloudsWithNormals.end();
2553  ++iter,++cloudsAdded)
2554  {
2555  pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
2556  if(_ui->comboBox_meshingApproach->currentIndex() == 0)
2557  {
2558  mesh = util3d::createMesh(
2559  iter->second,
2560  _ui->doubleSpinBox_gp3Radius->value(),
2561  _ui->doubleSpinBox_gp3Mu->value());
2562  }
2563  else
2564  {
2565  pcl::Poisson<pcl::PointXYZRGBNormal> poisson;
2566  poisson.setOutputPolygons(_ui->checkBox_poisson_outputPolygons->isEnabled()?_ui->checkBox_poisson_outputPolygons->isChecked():false);
2567  poisson.setManifold(_ui->checkBox_poisson_manifold->isChecked());
2568  poisson.setSamplesPerNode(_ui->doubleSpinBox_poisson_samples->value());
2569  int depth = _ui->spinBox_poisson_depth->value();
2570  if(depth == 0)
2571  {
2572  Eigen::Vector4f min,max;
2573  pcl::getMinMax3D(*iter->second, min, max);
2574  float mapLength = uMax3(max[0]-min[0], max[1]-min[1], max[2]-min[2]);
2575  depth = 12;
2576  for(int i=6; i<12; ++i)
2577  {
2578  if(mapLength/float(1<<i) < _ui->doubleSpinBox_poisson_targetPolygonSize->value())
2579  {
2580  depth = i;
2581  break;
2582  }
2583  }
2584  _progressDialog->appendText(tr("Poisson depth resolution chosen is %1, map size (m) = %2x%3x%4")
2585  .arg(depth)
2586  .arg(int(max[0]-min[0]))
2587  .arg(int(max[1]-min[1]))
2588  .arg(int(max[2]-min[2])));
2589  QApplication::processEvents();
2590  uSleep(100);
2591  QApplication::processEvents();
2592  }
2593  poisson.setDepth(depth);
2594  poisson.setIsoDivide(_ui->spinBox_poisson_iso->value());
2595  poisson.setSolverDivide(_ui->spinBox_poisson_solver->value());
2596  poisson.setMinDepth(_ui->spinBox_poisson_minDepth->value());
2597  poisson.setPointWeight(_ui->doubleSpinBox_poisson_pointWeight->value());
2598  poisson.setScale(_ui->doubleSpinBox_poisson_scale->value());
2599  poisson.setInputCloud(iter->second);
2600  poisson.reconstruct(*mesh);
2601  }
2602 
2603  _progressDialog->appendText(tr("Mesh %1 created with %2 polygons (%3/%4).").arg(iter->first).arg(mesh->polygons.size()).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2604  QApplication::processEvents();
2605 
2606  if(mesh->polygons.size()>0)
2607  {
2608  TexturingState texturingState(_progressDialog, false);
2609 
2610  if(!_ui->checkBox_fromDepth->isChecked() && !_scansHaveRGB)
2611  {
2612  // When laser scans are exported, convert Intensity to GrayScale
2613  int maxIntensity = 1;
2614  // first: get max intensity
2615  for(size_t i=0; i<iter->second->size(); ++i)
2616  {
2617  int intensity =
2618  int(iter->second->points[i].r) |
2619  int(iter->second->points[i].g) << 8 |
2620  int(iter->second->points[i].b) << 16 |
2621  int(iter->second->points[i].a) << 24;
2622  if(intensity > maxIntensity)
2623  {
2624  maxIntensity = intensity;
2625  }
2626  }
2627  // second: convert to grayscale
2628  for(size_t i=0; i<iter->second->size(); ++i)
2629  {
2630  int intensity =
2631  int(iter->second->points[i].r) |
2632  int(iter->second->points[i].g) << 8 |
2633  int(iter->second->points[i].b) << 16 |
2634  int(iter->second->points[i].a) << 24;
2635  intensity = intensity*255/maxIntensity;
2636  iter->second->points[i].r = (unsigned char)intensity;
2637  iter->second->points[i].g = (unsigned char)intensity;
2638  iter->second->points[i].b = (unsigned char)intensity;
2639  iter->second->points[i].a = (unsigned char)255;
2640  }
2641  }
2642 
2643  util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
2644  mesh,
2645  _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
2646  _ui->spinBox_meshMaxPolygons->isEnabled()?_ui->spinBox_meshMaxPolygons->value():0,
2647  iter->second,
2648  (float)_ui->doubleSpinBox_transferColorRadius->value(),
2649  !(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()),
2650  _ui->checkBox_cleanMesh->isChecked(),
2651  _ui->spinBox_mesh_minClusterSize->value(),
2652  &texturingState);
2653  meshes.insert(std::make_pair(iter->first, mesh));
2654  }
2655  else
2656  {
2657  _progressDialog->appendText(tr("No polygons created for cloud %1!").arg(iter->first), Qt::darkYellow);
2658  _progressDialog->setAutoClose(false);
2659  }
2660 
2661  _progressDialog->incrementStep(_ui->checkBox_assemble->isChecked()?poses.size():1);
2662  QApplication::processEvents();
2663  if(_canceled)
2664  {
2665  return false;
2666  }
2667  }
2668  }
2669  }
2670  else if(_ui->checkBox_meshing->isChecked())
2671  {
2672  std::string msg = uFormat("Some clouds are 2D laser scans. Meshing can be done only from RGB-D clouds or 3D laser scans.");
2673  _progressDialog->appendText(msg.c_str(), Qt::darkYellow);
2674  UWARN(msg.c_str());
2675  }
2676  else if(_ui->checkBox_cameraProjection->isEnabled() &&
2677  _ui->checkBox_cameraProjection->isChecked() &&
2678  cloudsWithNormals.size()==1 && cloudsWithNormals.begin()->first==0) // only for assembled point cloud
2679  {
2680  _progressDialog->appendText(tr("Camera projection..."));
2681  QApplication::processEvents();
2682  uSleep(100);
2683  QApplication::processEvents();
2684 
2685  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr assembledCloud = cloudsWithNormals.begin()->second;
2686 
2687  std::map<int, Transform> cameraPoses;
2688  std::map<int, std::vector<CameraModel> > cameraModels;
2689  for(std::map<int, Transform>::const_iterator iter=poses.lower_bound(0); iter!=poses.end(); ++iter)
2690  {
2691  std::vector<CameraModel> models;
2692  std::vector<StereoCameraModel> stereoModels;
2693  if(cachedSignatures.contains(iter->first))
2694  {
2695  const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
2696  models = data.cameraModels();
2697  stereoModels = data.stereoCameraModels();
2698  }
2699  else if(_dbDriver)
2700  {
2701  _dbDriver->getCalibration(iter->first, models, stereoModels);
2702  }
2703 
2704  if(stereoModels.size())
2705  {
2706  models.clear();
2707  for(size_t i=0; i<stereoModels.size(); ++i)
2708  {
2709  models.push_back(stereoModels[i].left());
2710  }
2711  }
2712 
2713  if(models.size() == 0 || !models[0].isValidForProjection())
2714  {
2715  models.clear();
2716  }
2717 
2718  if(!models.empty() && models[0].imageWidth() != 0 && models[0].imageHeight() != 0)
2719  {
2720  cameraPoses.insert(std::make_pair(iter->first, iter->second));
2721  cameraModels.insert(std::make_pair(iter->first, models));
2722  }
2723  else
2724  {
2725  UWARN("%d node has invalid camera models, ignoring it.", iter->first);
2726  }
2727  }
2728  if(!cameraPoses.empty())
2729  {
2730  TexturingState texturingState(_progressDialog, true);
2731  _progressDialog->setMaximumSteps(_progressDialog->maximumSteps() + assembledCloud->size()/10000+1 + cameraPoses.size());
2732  std::vector<float> roiRatios;
2733  QStringList strings = _ui->lineEdit_camProjRoiRatios->text().split(' ');
2734  if(!_ui->lineEdit_meshingTextureRoiRatios->text().isEmpty())
2735  {
2736  if(strings.size()==4)
2737  {
2738  roiRatios.resize(4);
2739  roiRatios[0]=strings[0].toDouble();
2740  roiRatios[1]=strings[1].toDouble();
2741  roiRatios[2]=strings[2].toDouble();
2742  roiRatios[3]=strings[3].toDouble();
2743  if(!(roiRatios[0]>=0.0f && roiRatios[0]<=1.0f &&
2744  roiRatios[1]>=0.0f && roiRatios[1]<=1.0f &&
2745  roiRatios[2]>=0.0f && roiRatios[2]<=1.0f &&
2746  roiRatios[3]>=0.0f && roiRatios[3]<=1.0f))
2747  {
2748  roiRatios.clear();
2749  }
2750  }
2751  if(roiRatios.empty())
2752  {
2753  QString msg = tr("Wrong ROI format. Region of Interest (ROI) must "
2754  "have 4 values [left right top bottom] between 0 and 1 "
2755  "separated by space (%1), ignoring it for projecting cameras...")
2756  .arg(_ui->lineEdit_camProjRoiRatios->text());
2757  UWARN(msg.toStdString().c_str());
2758  _progressDialog->appendText(msg, Qt::darkYellow);
2759  _progressDialog->setAutoClose(false);
2760  }
2761  }
2762 
2763  std::map<int, std::vector<rtabmap::CameraModel> > cameraModelsProj;
2764  if(_ui->spinBox_camProjDecimation->value()>1)
2765  {
2766  for(std::map<int, std::vector<rtabmap::CameraModel> >::iterator iter=cameraModels.begin();
2767  iter!=cameraModels.end();
2768  ++iter)
2769  {
2770  std::vector<rtabmap::CameraModel> models;
2771  for(size_t i=0; i<iter->second.size(); ++i)
2772  {
2773  models.push_back(iter->second[i].scaled(1.0/double(_ui->spinBox_camProjDecimation->value())));
2774  }
2775  cameraModelsProj.insert(std::make_pair(iter->first, models));
2776  }
2777  }
2778  else
2779  {
2780  cameraModelsProj = cameraModels;
2781  }
2782 
2783  cv::Mat projMask;
2784  if(!_ui->lineEdit_camProjMaskFilePath->text().isEmpty())
2785  {
2786  projMask = cv::imread(_ui->lineEdit_camProjMaskFilePath->text().toStdString(), cv::IMREAD_GRAYSCALE);
2787  if(_ui->spinBox_camProjDecimation->value()>1)
2788  {
2789  cv::Mat out = projMask;
2790  cv::resize(projMask, out, cv::Size(), 1.0f/float(_ui->spinBox_camProjDecimation->value()), 1.0f/float(_ui->spinBox_camProjDecimation->value()), cv::INTER_NEAREST);
2791  projMask = out;
2792  }
2793  }
2794 
2795  std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > pointToPixel;
2796  pointToPixel = util3d::projectCloudToCameras(
2797  *assembledCloud,
2798  cameraPoses,
2799  cameraModelsProj,
2800  _ui->doubleSpinBox_camProjMaxDistance->value(),
2801  _ui->doubleSpinBox_camProjMaxAngle->value()*M_PI/180.0,
2802  roiRatios,
2803  projMask,
2804  _ui->checkBox_camProjDistanceToCamPolicy->isChecked(),
2805  &texturingState);
2806 
2807  if(texturingState.isCanceled())
2808  {
2809  return false;
2810  }
2811 
2812  // color the cloud
2813  UASSERT(pointToPixel.empty() || pointToPixel.size() == assembledCloud->size());
2814  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr assembledCloudValidPoints;
2815  if(!_ui->checkBox_camProjKeepPointsNotSeenByCameras->isChecked())
2816  {
2817  assembledCloudValidPoints.reset(new pcl::PointCloud<pcl::PointXYZRGBNormal>());
2818  assembledCloudValidPoints->resize(assembledCloud->size());
2819  }
2820  if(_ui->comboBox_camProjExportCamera->isEnabled() &&
2821  _ui->comboBox_camProjExportCamera->currentIndex()>0)
2822  {
2823  textureVertexToPixels.resize(assembledCloud->size());
2824  }
2825 
2826  if(_ui->checkBox_camProjRecolorPoints->isChecked())
2827  {
2828  int imagesDone = 1;
2829  for(std::map<int, rtabmap::Transform>::iterator iter=cameraPoses.begin(); iter!=cameraPoses.end() && !_canceled; ++iter)
2830  {
2831  int nodeID = iter->first;
2832 
2833  cv::Mat image;
2834  if(cachedSignatures.contains(nodeID) && !cachedSignatures.value(nodeID).sensorData().imageCompressed().empty())
2835  {
2836  cachedSignatures.value(nodeID).sensorData().uncompressDataConst(&image, 0);
2837  }
2838  else if(_dbDriver)
2839  {
2840  SensorData data;
2841  _dbDriver->getNodeData(nodeID, data, true, false, false, false);
2842  data.uncompressDataConst(&image, 0);
2843  }
2844  if(!image.empty())
2845  {
2846 
2847  if(_ui->spinBox_camProjDecimation->value()>1)
2848  {
2849  image = util2d::decimate(image, _ui->spinBox_camProjDecimation->value());
2850  }
2851 
2852  UASSERT(cameraModelsProj.find(nodeID) != cameraModelsProj.end());
2853  int modelsSize = cameraModelsProj.at(nodeID).size();
2854  for(size_t i=0; i<pointToPixel.size(); ++i)
2855  {
2856  int cameraIndex = pointToPixel[i].first.second;
2857  if(nodeID == pointToPixel[i].first.first && cameraIndex>=0)
2858  {
2859  int subImageWidth = image.cols / modelsSize;
2860  cv::Mat subImage = image(cv::Range::all(), cv::Range(cameraIndex*subImageWidth, (cameraIndex+1)*subImageWidth));
2861 
2862  int x = pointToPixel[i].second.x * (float)subImage.cols;
2863  int y = pointToPixel[i].second.y * (float)subImage.rows;
2864  UASSERT(x>=0 && x<subImage.cols);
2865  UASSERT(y>=0 && y<subImage.rows);
2866 
2867  pcl::PointXYZRGBNormal & pt = assembledCloud->at(i);
2868  if(subImage.type()==CV_8UC3)
2869  {
2870  cv::Vec3b bgr = subImage.at<cv::Vec3b>(y, x);
2871  pt.b = bgr[0];
2872  pt.g = bgr[1];
2873  pt.r = bgr[2];
2874  }
2875  else
2876  {
2877  UASSERT(subImage.type()==CV_8UC1);
2878  pt.r = pt.g = pt.b = subImage.at<unsigned char>(pointToPixel[i].second.y * subImage.rows, pointToPixel[i].second.x * subImage.cols);
2879  }
2880  }
2881  }
2882  }
2883  QString msg = tr("Processed %1/%2 images").arg(imagesDone++).arg(cameraPoses.size());
2884  UINFO(msg.toStdString().c_str());
2886  QApplication::processEvents();
2887  }
2888  }
2889 
2890  pcl::IndicesPtr validIndices(new std::vector<int>(pointToPixel.size()));
2891  size_t oi = 0;
2892  for(size_t i=0; i<pointToPixel.size() && !_canceled; ++i)
2893  {
2894  pcl::PointXYZRGBNormal & pt = assembledCloud->at(i);
2895  if(pointToPixel[i].first.first <=0)
2896  {
2897  if(_ui->checkBox_camProjRecolorPoints->isChecked() && !_ui->checkBox_fromDepth->isChecked() && !_scansHaveRGB)
2898  {
2899  pt.r = 255;
2900  pt.g = 0;
2901  pt.b = 0;
2902  pt.a = 255;
2903  }
2904  }
2905  else
2906  {
2907  int nodeID = pointToPixel[i].first.first;
2908  int cameraIndex = pointToPixel[i].first.second;
2909  int exportedId = nodeID;
2910  if(_ui->comboBox_camProjExportCamera->currentIndex() == 2)
2911  {
2912  exportedId = cameraIndex+1;
2913  }
2914  else if(_ui->comboBox_camProjExportCamera->currentIndex() == 3)
2915  {
2916  UASSERT_MSG(cameraIndex<10, "Exporting cam id as NodeId+CamIndex is only supported when the number of cameras per node < 10.");
2917  exportedId = nodeID*10 + cameraIndex;
2918  }
2919 
2920  if(assembledCloudValidPoints.get())
2921  {
2922  if(!textureVertexToPixels.empty())
2923  {
2924  textureVertexToPixels[oi].insert(std::make_pair(exportedId, pointToPixel[i].second));
2925  }
2926  assembledCloudValidPoints->at(oi++) = pt;
2927  }
2928  else if(!textureVertexToPixels.empty())
2929  {
2930  textureVertexToPixels[i].insert(std::make_pair(exportedId, pointToPixel[i].second));
2931  }
2932  }
2933  }
2934 
2935  if(assembledCloudValidPoints.get())
2936  {
2937  assembledCloudValidPoints->resize(oi);
2938  cloudsWithNormals.begin()->second = assembledCloudValidPoints;
2939 
2940  if(!textureVertexToPixels.empty())
2941  {
2942  textureVertexToPixels.resize(oi);
2943  }
2944  }
2945 
2946  if(_canceled)
2947  {
2948  return false;
2949  }
2950  }
2951  }
2952 
2953  UDEBUG("");
2954 #ifdef RTABMAP_CPUTSDF
2955  if(tsdf.get())
2956  {
2957  _progressDialog->appendText(tr("CPU-TSDF: Creating mesh from TSDF volume..."));
2958  QApplication::processEvents();
2959  uSleep(100);
2960  QApplication::processEvents();
2961 
2962  cpu_tsdf::MarchingCubesTSDFOctree mc;
2963  mc.setMinWeight (_ui->doubleSpinBox_cputsdf_minWeight->value());
2964  mc.setInputTSDF (tsdf);
2965  mc.setColorByRGB (true);
2966  pcl::PolygonMesh::Ptr mesh (new pcl::PolygonMesh);
2967  mc.reconstruct (*mesh);
2968  _progressDialog->appendText(tr("CPU-TSDF: Creating mesh from TSDF volume...done! %1 polygons").arg(mesh->polygons.size()));
2969  meshes.clear();
2970 
2971  if(mesh->polygons.size()>0)
2972  {
2973 
2974  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr vertices (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2975  pcl::fromPCLPointCloud2 (mesh->cloud, *vertices);
2976 
2977  if(_ui->doubleSpinBox_cputsdf_flattenRadius->value()>0.0)
2978  {
2979  _progressDialog->appendText(tr("CPU-TSDF: Flattening mesh (radius=%1)...").arg(_ui->doubleSpinBox_cputsdf_flattenRadius->value()));
2980  QApplication::processEvents();
2981  uSleep(100);
2982  QApplication::processEvents();
2983 
2984  float min_dist = _ui->doubleSpinBox_cputsdf_flattenRadius->value();
2985  pcl::search::KdTree<pcl::PointXYZRGBNormal> vert_tree (true);
2986  vert_tree.setInputCloud (vertices);
2987  // Find duplicates
2988  std::vector<int> vertex_remap (vertices->size (), -1);
2989  int idx = 0;
2990  std::vector<int> neighbors;
2991  std::vector<float> dists;
2992  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr vertices_new(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2993  vertices_new->resize(vertices->size ());
2994  for (size_t i = 0; i < vertices->size (); i++)
2995  {
2996  if (vertex_remap[i] >= 0)
2997  continue;
2998  vertex_remap[i] = idx;
2999  vert_tree.radiusSearch (i, min_dist, neighbors, dists);
3000  for (size_t j = 1; j < neighbors.size (); j++)
3001  {
3002  if (dists[j] < min_dist)
3003  vertex_remap[neighbors[j]] = idx;
3004  }
3005  vertices_new->at(idx++) = vertices->at (i);
3006  }
3007  vertices_new->resize(idx);
3008  std::vector<size_t> faces_to_remove;
3009  size_t face_idx = 0;
3010  for (size_t i = 0; i < mesh->polygons.size (); i++)
3011  {
3012  pcl::Vertices &v = mesh->polygons[i];
3013  for (size_t j = 0; j < v.vertices.size (); j++)
3014  {
3015  v.vertices[j] = vertex_remap[v.vertices[j]];
3016  }
3017  if (!(v.vertices[0] == v.vertices[1] || v.vertices[1] == v.vertices[2] || v.vertices[2] == v.vertices[0]))
3018  {
3019  mesh->polygons[face_idx++] = mesh->polygons[i];
3020  }
3021  }
3022  mesh->polygons.resize (face_idx);
3023  pcl::toPCLPointCloud2 (*vertices_new, mesh->cloud);
3024  vertices = vertices_new;
3025  }
3026 
3027  pcl::fromPCLPointCloud2(mesh->cloud, *vertices);
3028  TexturingState texturingState(_progressDialog, false);
3029  util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
3030  mesh,
3031  _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
3032  _ui->spinBox_meshMaxPolygons->isEnabled()?_ui->spinBox_meshMaxPolygons->value():0,
3033  vertices,
3034  (float)_ui->doubleSpinBox_transferColorRadius->value(),
3035  !(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()),
3036  _ui->checkBox_cleanMesh->isChecked(),
3037  _ui->spinBox_mesh_minClusterSize->value(),
3038  &texturingState);
3039  meshes.insert(std::make_pair(0, mesh));
3040  }
3041  else
3042  {
3043  _progressDialog->appendText(tr("No polygons created TSDF volume!"), Qt::darkYellow);
3044  _progressDialog->setAutoClose(false);
3045  }
3046  }
3047 #endif
3048 #ifdef RTABMAP_OPENCHISEL
3049  if(chiselMap.get())
3050  {
3051  _progressDialog->appendText(tr("OpenChisel: Creating mesh from TSDF volume..."));
3052  QApplication::processEvents();
3053  uSleep(100);
3054  QApplication::processEvents();
3055 
3056  const chisel::MeshMap& meshMap = chiselMap->GetChunkManager().GetAllMeshes();
3057  pcl::PolygonMesh::Ptr mesh = chiselToPolygonMesh(meshMap);
3058 
3059  // To debug...
3060  //std::string filePly = _workingDirectory.toStdString()+"/"+"chisel.ply";
3061  //chiselMap->SaveAllMeshesToPLY(filePly);
3062  //UWARN("Saved %s", filePly.c_str());
3063 
3064  _progressDialog->appendText(tr("OpenChisel: Creating mesh from TSDF volume...done! %1 polygons").arg(mesh->polygons.size()));
3065 
3066  meshes.clear();
3067  if(mesh->polygons.size()>0)
3068  {
3069  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
3070  pcl::fromPCLPointCloud2(mesh->cloud, *mergedClouds);
3071  if(_ui->checkBox_openchisel_mergeVertices->isChecked())
3072  {
3073  _progressDialog->appendText(tr("Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").arg(mergedClouds->size()).arg(mesh->polygons.size()));
3074  QApplication::processEvents();
3075 
3076  mesh->polygons = util3d::filterCloseVerticesFromMesh(
3077  mergedClouds,
3078  mesh->polygons,
3079  _ui->doubleSpinBox_voxelSize_assembled->value()/2.0,
3080  M_PI/4,
3081  true);
3082 
3083  // filter invalid polygons
3084  unsigned int count = mesh->polygons.size();
3085  mesh->polygons = util3d::filterInvalidPolygons(mesh->polygons);
3086  _progressDialog->appendText(tr("Filtered %1 invalid polygons.").arg(count-mesh->polygons.size()));
3087  QApplication::processEvents();
3088 
3089  // filter not used vertices
3090  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
3091  std::vector<pcl::Vertices> filteredPolygons;
3092  count = mergedClouds->size();
3093  util3d::filterNotUsedVerticesFromMesh(*mergedClouds, mesh->polygons, *filteredCloud, filteredPolygons);
3094  mergedClouds = filteredCloud;
3095  pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
3096  mesh->polygons = filteredPolygons;
3097  _progressDialog->appendText(tr("Filtered %1 duplicate vertices.").arg(count-mergedClouds->size()));
3098  QApplication::processEvents();
3099  }
3100  TexturingState texturingState(_progressDialog, false);
3101  util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
3102  mesh,
3103  _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
3104  _ui->spinBox_meshMaxPolygons->isEnabled()?_ui->spinBox_meshMaxPolygons->value():0,
3105  mergedClouds,
3106  (float)_ui->doubleSpinBox_transferColorRadius->value(),
3107  !(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()),
3108  _ui->checkBox_cleanMesh->isChecked(),
3109  _ui->spinBox_mesh_minClusterSize->value(),
3110  &texturingState);
3111  meshes.insert(std::make_pair(0, mesh));
3112  }
3113  else
3114  {
3115  _progressDialog->appendText(tr("No polygons created TSDF volume!"), Qt::darkYellow);
3116  _progressDialog->setAutoClose(false);
3117  }
3118  }
3119 #endif
3120 
3121  UDEBUG("");
3122  if(_canceled)
3123  {
3124  return false;
3125  }
3126 
3127  // texture mesh
3128  UDEBUG("texture mapping=%d", _ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()?1:0);
3129  if(!has2dScans && !meshes.empty() && _ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked())
3130  {
3131  _progressDialog->appendText(tr("Texturing..."));
3132  QApplication::processEvents();
3133  uSleep(100);
3134  QApplication::processEvents();
3135 
3136  int i=0;
3137  for(std::map<int, pcl::PolygonMesh::Ptr>::iterator iter=meshes.begin();
3138  iter!= meshes.end();
3139  ++iter)
3140  {
3141  std::map<int, Transform> cameras;
3142  if(iter->first == 0)
3143  {
3144  cameras = poses;
3145  }
3146  else
3147  {
3148  UASSERT(uContains(poses, iter->first));
3149  cameras.insert(std::make_pair(iter->first, _ui->checkBox_assemble->isChecked()?poses.at(iter->first):Transform::getIdentity()));
3150  }
3151  std::map<int, Transform> cameraPoses;
3152  std::map<int, std::vector<CameraModel> > cameraModels;
3153  std::map<int, cv::Mat > cameraDepths;
3154  int ignoredCameras = 0;
3155  for(std::map<int, Transform>::iterator jter=cameras.begin(); jter!=cameras.end(); ++jter)
3156  {
3157  if(validCameras.find(jter->first) != validCameras.end())
3158  {
3159  std::vector<CameraModel> models;
3160  std::vector<StereoCameraModel> stereoModels;
3161  bool cacheHasCompressedImage = false;
3162  if(cachedSignatures.contains(jter->first))
3163  {
3164  const SensorData & data = cachedSignatures.find(jter->first)->sensorData();
3165  models = data.cameraModels();
3166  stereoModels = data.stereoCameraModels();
3167  cacheHasCompressedImage = !data.imageCompressed().empty();
3168  }
3169  else if(_dbDriver)
3170  {
3171  _dbDriver->getCalibration(jter->first, models, stereoModels);
3172  }
3173 
3174  bool stereo=false;
3175  if(stereoModels.size())
3176  {
3177  stereo = true;
3178  models.clear();
3179  for(size_t i=0; i<stereoModels.size(); ++i)
3180  {
3181  models.push_back(stereoModels[i].left());
3182  }
3183  }
3184 
3185  if(models.size() == 0 || !models[0].isValidForProjection())
3186  {
3187  models.clear();
3188  }
3189 
3190  if(!jter->second.isNull() && models.size())
3191  {
3192  cv::Mat depth;
3193  bool blurryImage = false;
3194  bool getDepth = !stereo && _ui->doubleSpinBox_meshingTextureMaxDepthError->value() >= 0.0f;
3195  cv::Mat img;
3196  std::vector<float> velocity;
3197  if(models[0].imageWidth() == 0 || models[0].imageHeight() == 0)
3198  {
3199  // we are using an old database format (image size not saved in calibrations), we should
3200  // uncompress images to get their size
3201  if(cacheHasCompressedImage)
3202  {
3203  cachedSignatures.find(jter->first)->sensorData().uncompressDataConst(&img, getDepth?&depth:0);
3204  velocity = cachedSignatures.find(jter->first)->getVelocity();
3205  }
3206  else if(_dbDriver)
3207  {
3208  SensorData data;
3209  _dbDriver->getNodeData(jter->first, data, true, false, false, false);
3210  data.uncompressDataConst(&img, getDepth?&depth:0);
3211 
3212  if(_ui->checkBox_cameraFilter->isChecked() &&
3213  (_ui->doubleSpinBox_cameraFilterVel->value()>0.0 || _ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
3214  {
3215  Transform p,gt;
3216  int m,w;
3217  std::string l;
3218  double s;
3219  GPS gps;
3220  EnvSensors sensors;
3221  _dbDriver->getNodeInfo(jter->first, p, m, w, l, s, gt, velocity, gps, sensors);
3222  }
3223  }
3224  cv::Size imageSize = img.size();
3225  imageSize.width /= models.size();
3226  for(unsigned int i=0; i<models.size(); ++i)
3227  {
3228  models[i].setImageSize(imageSize);
3229  }
3230  }
3231  else
3232  {
3233  bool getImg = _ui->checkBox_cameraFilter->isChecked() && _ui->doubleSpinBox_laplacianVariance->value()>0.0;
3234  // get just the depth
3235  if(cacheHasCompressedImage)
3236  {
3237  cachedSignatures.find(jter->first)->sensorData().uncompressDataConst(getImg?&img:0, getDepth?&depth:0);
3238  velocity = cachedSignatures.find(jter->first)->getVelocity();
3239  }
3240  else if(_dbDriver)
3241  {
3242  SensorData data;
3243  _dbDriver->getNodeData(jter->first, data, true, false, false, false);
3244  data.uncompressDataConst(getImg?&img:0, getDepth?&depth:0);
3245 
3246  if(_ui->checkBox_cameraFilter->isChecked() &&
3247  (_ui->doubleSpinBox_cameraFilterVel->value()>0.0 || _ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
3248  {
3249  Transform p,gt;
3250  int m,w;
3251  std::string l;
3252  double s;
3253  GPS gps;
3254  EnvSensors sensors;
3255  _dbDriver->getNodeInfo(jter->first, p, m, w, l, s, gt, velocity, gps, sensors);
3256  }
3257  }
3258  }
3259  if(_ui->checkBox_cameraFilter->isChecked())
3260  {
3261  std::string msg;
3262  if(!blurryImage &&
3263  (_ui->doubleSpinBox_cameraFilterVel->value()>0.0 || _ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
3264  {
3265  if(velocity.size() == 6)
3266  {
3267  float transVel = uMax3(fabs(velocity[0]), fabs(velocity[1]), fabs(velocity[2]));
3268  float rotVel = uMax3(fabs(velocity[3]), fabs(velocity[4]), fabs(velocity[5]));
3269  if(_ui->doubleSpinBox_cameraFilterVel->value()>0.0 && transVel > _ui->doubleSpinBox_cameraFilterVel->value())
3270  {
3271  msg = uFormat("Fast motion detected for camera %d (speed=%f m/s > thr=%f m/s), camera is ignored for texturing.", jter->first, transVel, _ui->doubleSpinBox_cameraFilterVel->value());
3272  blurryImage = true;
3273  }
3274  else if(_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0 && rotVel > _ui->doubleSpinBox_cameraFilterVelRad->value())
3275  {
3276  msg = uFormat("Fast motion detected for camera %d (speed=%f rad/s > thr=%f rad/s), camera is ignored for texturing.", jter->first, rotVel, _ui->doubleSpinBox_cameraFilterVelRad->value());
3277  blurryImage = true;
3278  }
3279  }
3280  else
3281  {
3282  UWARN("Camera motion filtering is set, but velocity of camera %d is not available.", jter->first);
3283  }
3284  }
3285 
3286  if(!blurryImage && !img.empty() && _ui->doubleSpinBox_laplacianVariance->value()>0.0)
3287  {
3288  cv::Mat imgLaplacian;
3289  cv::Laplacian(img, imgLaplacian, CV_16S);
3290  cv::Mat m, s;
3291  cv::meanStdDev(imgLaplacian, m, s);
3292  double stddev_pxl = s.at<double>(0);
3293  double var = stddev_pxl*stddev_pxl;
3294  if(var < _ui->doubleSpinBox_laplacianVariance->value())
3295  {
3296  blurryImage = true;
3297  msg = uFormat("Camera's image %d is detected as blurry (var=%f, thr=%f), camera is ignored for texturing.", jter->first, var, _ui->doubleSpinBox_laplacianVariance->value());
3298  }
3299  }
3300  if(blurryImage)
3301  {
3302  _progressDialog->appendText(msg.c_str());
3303  QApplication::processEvents();
3304  ++ignoredCameras;
3305  }
3306  }
3307 
3308  if(!blurryImage && models[0].imageWidth() != 0 && models[0].imageHeight() != 0)
3309  {
3310  cameraPoses.insert(std::make_pair(jter->first, jter->second));
3311  cameraModels.insert(std::make_pair(jter->first, models));
3312  if(!depth.empty())
3313  {
3314  cameraDepths.insert(std::make_pair(jter->first, depth));
3315  }
3316  }
3317  }
3318  }
3319  }
3320  if(ignoredCameras > (int)validCameras.size()/2)
3321  {
3322  std::string msg = uFormat("More than 50%% of the cameras (%d/%d) have been filtered for "
3323  "too fast motion and/or blur level. You may adjust the corresponding thresholds.",
3324  ignoredCameras, (int)validCameras.size());
3325  UWARN(msg.c_str());
3326  _progressDialog->appendText(msg.c_str(), Qt::darkYellow);
3327  _progressDialog->setAutoClose(false);
3328  QApplication::processEvents();
3329  }
3330 
3331  if(cameraPoses.size() && iter->second->polygons.size())
3332  {
3333  pcl::TextureMesh::Ptr textureMesh(new pcl::TextureMesh);
3334  std::map<int, std::vector<int> >::iterator oter = organizedIndices.find(iter->first);
3335  std::map<int, cv::Size>::iterator ster = organizedCloudSizes.find(iter->first);
3336  if(iter->first != 0 && oter != organizedIndices.end())
3337  {
3338  UASSERT(ster!=organizedCloudSizes.end()&&ster->first == oter->first);
3339  UDEBUG("Texture by pixels");
3340  textureMesh->cloud = iter->second->cloud;
3341  textureMesh->tex_polygons.push_back(iter->second->polygons);
3342  int w = ster->second.width;
3343  int h = ster->second.height;
3344  UASSERT(w > 1 && h > 1);
3345  if(textureMesh->tex_polygons.size() && textureMesh->tex_polygons[0].size())
3346  {
3347  textureMesh->tex_coordinates.resize(1);
3348 
3349  //tex_coordinates should be linked to polygon vertices
3350  int polygonSize = (int)textureMesh->tex_polygons[0][0].vertices.size();
3351  textureMesh->tex_coordinates[0].resize(polygonSize*textureMesh->tex_polygons[0].size());
3352  for(unsigned int i=0; i<textureMesh->tex_polygons[0].size(); ++i)
3353  {
3354  const pcl::Vertices & vertices = textureMesh->tex_polygons[0][i];
3355  UASSERT(polygonSize == (int)vertices.vertices.size());
3356  for(int k=0; k<polygonSize; ++k)
3357  {
3358  //uv
3359  UASSERT((int)vertices.vertices[k] < (int)oter->second.size());
3360  int originalVertex = oter->second[vertices.vertices[k]];
3361  textureMesh->tex_coordinates[0][i*polygonSize+k] = Eigen::Vector2f(
3362  float(originalVertex % w) / float(w), // u
3363  float(h - originalVertex / w) / float(h)); // v
3364  }
3365  }
3366 
3367  pcl::TexMaterial mesh_material;
3368  mesh_material.tex_d = 1.0f;
3369  mesh_material.tex_Ns = 75.0f;
3370  mesh_material.tex_illum = 1;
3371 
3372  std::stringstream tex_name;
3373  tex_name << "material_" << iter->first;
3374  tex_name >> mesh_material.tex_name;
3375 
3376  mesh_material.tex_file = uFormat("%d", iter->first);
3377  textureMesh->tex_materials.push_back(mesh_material);
3378  }
3379  else
3380  {
3381  UWARN("No polygons for mesh %d!?", iter->first);
3382  }
3383  }
3384  else
3385  {
3386  UDEBUG("Texture by projection");
3387 
3388  if(cameraPoses.size() && _ui->checkBox_cameraFilter->isChecked())
3389  {
3390  int before = (int)cameraPoses.size();
3391  cameraPoses = graph::radiusPosesFiltering(cameraPoses,
3392  _ui->doubleSpinBox_cameraFilterRadius->value(),
3393  _ui->doubleSpinBox_cameraFilterAngle->value());
3394  for(std::map<int, std::vector<CameraModel> >::iterator modelIter = cameraModels.begin(); modelIter!=cameraModels.end();)
3395  {
3396  if(cameraPoses.find(modelIter->first)==cameraPoses.end())
3397  {
3398  cameraModels.erase(modelIter++);
3399  cameraDepths.erase(modelIter->first);
3400  }
3401  else
3402  {
3403  ++modelIter;
3404  }
3405  }
3406  _progressDialog->appendText(tr("Camera filtering: keeping %1/%2/%3 cameras for texturing.").arg(cameraPoses.size()).arg(before).arg(validCameras.size()));
3407  QApplication::processEvents();
3408  uSleep(100);
3409  QApplication::processEvents();
3410  }
3411 
3412  if(_canceled)
3413  {
3414  return false;
3415  }
3416 
3417  TexturingState texturingState(_progressDialog, true);
3418  _progressDialog->setMaximumSteps(_progressDialog->maximumSteps()+iter->second->polygons.size()/10000+1);
3419  if(cameraModels.size() && cameraModels.begin()->second.size()>1)
3420  {
3421  _progressDialog->setMaximumSteps(_progressDialog->maximumSteps()+cameraModels.size()*(cameraModels.begin()->second.size()-1));
3422  }
3423 
3424  std::vector<float> roiRatios;
3425  QStringList strings = _ui->lineEdit_meshingTextureRoiRatios->text().split(' ');
3426  if(!_ui->lineEdit_meshingTextureRoiRatios->text().isEmpty())
3427  {
3428  if(strings.size()==4)
3429  {
3430  roiRatios.resize(4);
3431  roiRatios[0]=strings[0].toDouble();
3432  roiRatios[1]=strings[1].toDouble();
3433  roiRatios[2]=strings[2].toDouble();
3434  roiRatios[3]=strings[3].toDouble();
3435  if(!(roiRatios[0]>=0.0f && roiRatios[0]<=1.0f &&
3436  roiRatios[1]>=0.0f && roiRatios[1]<=1.0f &&
3437  roiRatios[2]>=0.0f && roiRatios[2]<=1.0f &&
3438  roiRatios[3]>=0.0f && roiRatios[3]<=1.0f))
3439  {
3440  roiRatios.clear();
3441  }
3442  }
3443  if(roiRatios.empty())
3444  {
3445  QString msg = tr("Wrong ROI format. Region of Interest (ROI) must have 4 "
3446  "values [left right top bottom] between 0 and 1 "
3447  "separated by space (%1), ignoring it for texturing...")
3448  .arg(_ui->lineEdit_meshingTextureRoiRatios->text());
3449  UWARN(msg.toStdString().c_str());
3450  _progressDialog->appendText(msg, Qt::darkYellow);
3451  _progressDialog->setAutoClose(false);
3452  }
3453  }
3454 
3455  textureMesh = util3d::createTextureMesh(
3456  iter->second,
3457  cameraPoses,
3458  cameraModels,
3459  cameraDepths,
3460  _ui->doubleSpinBox_meshingTextureMaxDistance->value(),
3461  _ui->doubleSpinBox_meshingTextureMaxDepthError->value(),
3462  _ui->doubleSpinBox_meshingTextureMaxAngle->value()*M_PI/180.0,
3463  _ui->spinBox_mesh_minTextureClusterSize->value(),
3464  roiRatios,
3465  &texturingState,
3466  cameraPoses.size()>1?&textureVertexToPixels:0, // only get vertexToPixels if merged clouds with multi textures
3467  _ui->checkBox_distanceToCamPolicy->isChecked());
3468 
3469  if(_canceled)
3470  {
3471  return false;
3472  }
3473 
3474  // Remove occluded polygons (polygons with no texture)
3475  if(_ui->checkBox_cleanMesh->isChecked())
3476  {
3477  unsigned int totalSize = 0;
3478  for(unsigned int t=0; t<textureMesh->tex_polygons.size(); ++t)
3479  {
3480  totalSize+=textureMesh->tex_polygons[t].size();
3481  }
3482 
3483  util3d::cleanTextureMesh(*textureMesh, _ui->spinBox_mesh_minClusterSize->value());
3484 
3485  unsigned int totalSizeAfter = 0;
3486  for(unsigned int t=0; t<textureMesh->tex_polygons.size(); ++t)
3487  {
3488  totalSizeAfter+=textureMesh->tex_polygons[t].size();
3489  }
3490  _progressDialog->appendText(tr("Cleaned texture mesh: %1 -> %2 polygons").arg(totalSize).arg(totalSizeAfter));
3491  }
3492  }
3493 
3494  textureMeshes.insert(std::make_pair(iter->first, textureMesh));
3495  }
3496  else if(cameraPoses.size() == 0)
3497  {
3498  _progressDialog->appendText(tr("No cameras from %1 poses with valid calibration found!").arg(poses.size()), Qt::darkYellow);
3499  _progressDialog->setAutoClose(false);
3500  UWARN("No camera poses!?");
3501  }
3502  else
3503  {
3504  _progressDialog->appendText(tr("No polygons!?"), Qt::darkYellow);
3505  _progressDialog->setAutoClose(false);
3506  UWARN("No polygons!");
3507  }
3508 
3509  _progressDialog->appendText(tr("TextureMesh %1 created [cameras=%2] (%3/%4).").arg(iter->first).arg(cameraPoses.size()).arg(++i).arg(meshes.size()));
3511  QApplication::processEvents();
3512  if(_canceled)
3513  {
3514  return false;
3515  }
3516  }
3517 
3518  if(textureMeshes.size() > 1 && _ui->checkBox_assemble->isChecked())
3519  {
3520  UDEBUG("Concatenate texture meshes");
3521  _progressDialog->appendText(tr("Assembling %1 meshes...").arg(textureMeshes.size()));
3522  QApplication::processEvents();
3523  uSleep(100);
3524  QApplication::processEvents();
3525 
3526  pcl::TextureMesh::Ptr assembledMesh = util3d::concatenateTextureMeshes(uValuesList(textureMeshes));
3527  textureMeshes.clear();
3528  textureMeshes.insert(std::make_pair(0, assembledMesh));
3529  }
3530  }
3531 
3532  UDEBUG("");
3533  return true;
3534  }
3535  return false;
3536 }
3537 
3538 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > ExportCloudsDialog::getClouds(
3539  const std::map<int, Transform> & poses,
3540  const QMap<int, Signature> & cachedSignatures,
3541  const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
3542  const std::map<int, LaserScan> & cachedScans,
3543  const ParametersMap & parameters,
3544  bool & has2dScans,
3545  bool & scansHaveRGB) const
3546 {
3547  scansHaveRGB = false;
3548  has2dScans = false;
3549  std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
3550  int index=1;
3551  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr previousCloud;
3552  pcl::IndicesPtr previousIndices;
3553  Transform previousPose;
3554  for(std::map<int, Transform>::const_iterator iter = poses.lower_bound(1); iter!=poses.end() && !_canceled; ++iter, ++index)
3555  {
3556  int points = 0;
3557  int totalIndices = 0;
3558  if(!iter->second.isNull())
3559  {
3560  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
3561  pcl::IndicesPtr indices(new std::vector<int>);
3562  Transform localTransform = Transform::getIdentity();
3563  if(_ui->checkBox_regenerate->isChecked())
3564  {
3565  SensorData data;
3566  LaserScan scan;
3567  if(cachedSignatures.contains(iter->first))
3568  {
3569  const Signature & s = cachedSignatures.find(iter->first).value();
3570  data = s.sensorData();
3571  cv::Mat image,depth;
3572  data.uncompressData(
3573  _ui->checkBox_fromDepth->isChecked()?&image:0,
3574  _ui->checkBox_fromDepth->isChecked()?&depth:0,
3575  !_ui->checkBox_fromDepth->isChecked()?&scan:0);
3576  }
3577  else if(_dbDriver)
3578  {
3579  cv::Mat image,depth;
3580  _dbDriver->getNodeData(iter->first, data, _ui->checkBox_fromDepth->isChecked(), !_ui->checkBox_fromDepth->isChecked(), false, false);
3581  data.uncompressData(
3582  _ui->checkBox_fromDepth->isChecked()?&image:0,
3583  _ui->checkBox_fromDepth->isChecked()?&depth:0,
3584  !_ui->checkBox_fromDepth->isChecked()?&scan:0);
3585  }
3586 
3587  if(_ui->checkBox_fromDepth->isChecked() && !data.imageRaw().empty() && !data.depthOrRightRaw().empty())
3588  {
3589  cv::Mat depth = data.depthRaw();
3590  if(!depth.empty() && _ui->spinBox_fillDepthHoles->value() > 0)
3591  {
3592  depth = util2d::fillDepthHoles(depth, _ui->spinBox_fillDepthHoles->value(), float(_ui->spinBox_fillDepthHolesError->value())/100.f);
3593  }
3594 
3595  if(!depth.empty() &&
3596  !_ui->lineEdit_distortionModel->text().isEmpty() &&
3597  QFileInfo(_ui->lineEdit_distortionModel->text()).exists())
3598  {
3600  model.load(_ui->lineEdit_distortionModel->text().toStdString());
3601  depth = depth.clone();// make sure we are not modifying data in cached signatures.
3602  model.undistort(depth);
3603  }
3604 
3605  // bilateral filtering
3606  if(!depth.empty() && _ui->checkBox_bilateral->isChecked())
3607  {
3608  depth = util2d::fastBilateralFiltering(depth,
3609  _ui->doubleSpinBox_bilateral_sigmaS->value(),
3610  _ui->doubleSpinBox_bilateral_sigmaR->value());
3611  }
3612 
3613  if(!depth.empty())
3614  {
3615  data.setRGBDImage(data.imageRaw(), depth, data.cameraModels());
3616  }
3617 
3618  UASSERT(iter->first == data.id());
3619  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
3620  std::vector<float> roiRatios;
3621  if(!_ui->lineEdit_roiRatios->text().isEmpty())
3622  {
3623  QStringList values = _ui->lineEdit_roiRatios->text().split(' ');
3624  if(values.size() == 4)
3625  {
3626  roiRatios.resize(4);
3627  for(int i=0; i<values.size(); ++i)
3628  {
3629  roiRatios[i] = uStr2Float(values[i].toStdString().c_str());
3630  }
3631  }
3632  }
3633  cloudWithoutNormals = util3d::cloudRGBFromSensorData(
3634  data,
3635  _ui->spinBox_decimation->value() == 0?1:_ui->spinBox_decimation->value(),
3636  _ui->doubleSpinBox_maxDepth->value(),
3637  _ui->doubleSpinBox_minDepth->value(),
3638  indices.get(),
3639  parameters,
3640  roiRatios);
3641 
3642  if(cloudWithoutNormals->size())
3643  {
3644  // Don't voxelize if we create organized mesh
3645  if(!(_ui->comboBox_pipeline->currentIndex()==0 && _ui->checkBox_meshing->isChecked()) && _ui->doubleSpinBox_voxelSize_assembled->value()>0.0)
3646  {
3647  cloudWithoutNormals = util3d::voxelize(cloudWithoutNormals, indices, _ui->doubleSpinBox_voxelSize_assembled->value());
3648  indices->resize(cloudWithoutNormals->size());
3649  for(unsigned int i=0; i<indices->size(); ++i)
3650  {
3651  indices->at(i) = i;
3652  }
3653  }
3654 
3655  // view point
3656  Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
3657  if(data.cameraModels().size() && !data.cameraModels()[0].localTransform().isNull())
3658  {
3659  localTransform = data.cameraModels()[0].localTransform();
3660  viewPoint[0] = data.cameraModels()[0].localTransform().x();
3661  viewPoint[1] = data.cameraModels()[0].localTransform().y();
3662  viewPoint[2] = data.cameraModels()[0].localTransform().z();
3663  }
3664  else if(data.stereoCameraModels().size() && !data.stereoCameraModels()[0].localTransform().isNull())
3665  {
3666  localTransform = data.stereoCameraModels()[0].localTransform();
3667  viewPoint[0] = data.stereoCameraModels()[0].localTransform().x();
3668  viewPoint[1] = data.stereoCameraModels()[0].localTransform().y();
3669  viewPoint[2] = data.stereoCameraModels()[0].localTransform().z();
3670  }
3671 
3672  if(_ui->spinBox_normalKSearch->value()>0 || _ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
3673  {
3674  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
3675  pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
3676  if(_ui->doubleSpinBox_groundNormalsUp->value() > 0.0)
3677  {
3678  util3d::adjustNormalsToViewPoint(cloud, viewPoint, (float)_ui->doubleSpinBox_groundNormalsUp->value());
3679  }
3680  }
3681  else
3682  {
3683  pcl::copyPointCloud(*cloudWithoutNormals, *cloud);
3684  }
3685 
3686  if(_ui->checkBox_subtraction->isChecked() &&
3687  _ui->doubleSpinBox_subtractPointFilteringRadius->value() > 0.0)
3688  {
3689  pcl::IndicesPtr beforeSubtractionIndices = indices;
3690  if( cloud->size() &&
3691  previousCloud.get() != 0 &&
3692  previousIndices.get() != 0 &&
3693  previousIndices->size() &&
3694  !previousPose.isNull())
3695  {
3696  rtabmap::Transform t = iter->second.inverse() * previousPose;
3697  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformedCloud = rtabmap::util3d::transformPointCloud(previousCloud, t);
3699  cloud,
3700  indices,
3701  transformedCloud,
3702  previousIndices,
3703  _ui->doubleSpinBox_subtractPointFilteringRadius->value(),
3704  _ui->doubleSpinBox_subtractPointFilteringAngle->value(),
3705  _ui->spinBox_subtractFilteringMinPts->value());
3706  }
3707  previousCloud = cloud;
3708  previousIndices = beforeSubtractionIndices;
3709  previousPose = iter->second;
3710  }
3711  }
3712  }
3713  else if(!_ui->checkBox_fromDepth->isChecked() && !scan.isEmpty())
3714  {
3715  scan = util3d::commonFiltering(scan,
3716  _ui->spinBox_decimation_scan->value(),
3717  _ui->doubleSpinBox_rangeMin->value(),
3718  _ui->doubleSpinBox_rangeMax->value(),
3719  _ui->doubleSpinBox_voxelSize_assembled->value(),
3720  _ui->spinBox_normalKSearch->value(),
3721  _ui->doubleSpinBox_normalRadiusSearch->value());
3722 
3723  if(!scan.empty())
3724  {
3725  scansHaveRGB = scan.hasRGB();
3726  }
3727  localTransform = scan.localTransform();
3728  cloud = util3d::laserScanToPointCloudRGBNormal(scan, localTransform); // put in base frame by default
3729  indices->resize(cloud->size());
3730  for(unsigned int i=0; i<indices->size(); ++i)
3731  {
3732  indices->at(i) = i;
3733  }
3734  }
3735  else
3736  {
3737  int weight = 0;
3738  if(cachedSignatures.contains(iter->first))
3739  {
3740  const Signature & s = cachedSignatures.find(iter->first).value();
3741  weight = s.getWeight();
3742  }
3743  else if(_dbDriver)
3744  {
3745  _dbDriver->getWeight(iter->first, weight);
3746  }
3747  if(weight>=0) // don't show error for intermediate nodes
3748  {
3749  UERROR("Cloud %d not found in cache!", iter->first);
3750  }
3751  }
3752  }
3753  else if(_ui->checkBox_fromDepth->isChecked() && uContains(cachedClouds, iter->first))
3754  {
3755  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
3756  if(!_ui->checkBox_meshing->isChecked() &&
3757  _ui->doubleSpinBox_voxelSize_assembled->value() > 0.0)
3758  {
3759  cloudWithoutNormals = util3d::voxelize(
3760  cachedClouds.at(iter->first).first,
3761  cachedClouds.at(iter->first).second,
3762  _ui->doubleSpinBox_voxelSize_assembled->value());
3763 
3764  //generate indices for all points (they are all valid)
3765  indices->resize(cloudWithoutNormals->size());
3766  for(unsigned int i=0; i<cloudWithoutNormals->size(); ++i)
3767  {
3768  indices->at(i) = i;
3769  }
3770  }
3771  else
3772  {
3773  cloudWithoutNormals = cachedClouds.at(iter->first).first;
3774  indices = cachedClouds.at(iter->first).second;
3775  }
3776 
3777  // view point
3778  Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
3779  std::vector<CameraModel> models;
3780  std::vector<StereoCameraModel> stereoModels;
3781  if(cachedSignatures.contains(iter->first))
3782  {
3783  const Signature & s = cachedSignatures.find(iter->first).value();
3784  models = s.sensorData().cameraModels();
3785  stereoModels = s.sensorData().stereoCameraModels();
3786  }
3787  else if(_dbDriver)
3788  {
3789  _dbDriver->getCalibration(iter->first, models, stereoModels);
3790  }
3791 
3792  if(models.size() && !models[0].localTransform().isNull())
3793  {
3794  localTransform = models[0].localTransform();
3795  viewPoint[0] = models[0].localTransform().x();
3796  viewPoint[1] = models[0].localTransform().y();
3797  viewPoint[2] = models[0].localTransform().z();
3798  }
3799  else if(stereoModels.size() && !stereoModels[0].localTransform().isNull())
3800  {
3801  localTransform = stereoModels[0].localTransform();
3802  viewPoint[0] = stereoModels[0].localTransform().x();
3803  viewPoint[1] = stereoModels[0].localTransform().y();
3804  viewPoint[2] = stereoModels[0].localTransform().z();
3805  }
3806  else
3807  {
3808  _progressDialog->appendText(tr("Cached cloud %1 is not found in cached data, the view point for normal computation will not be set (%2/%3).").arg(iter->first).arg(index).arg(poses.size()), Qt::darkYellow);
3809  }
3810 
3811  if(_ui->spinBox_normalKSearch->value()>0 || _ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
3812  {
3813  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
3814  pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
3815  if(_ui->doubleSpinBox_groundNormalsUp->value() > 0.0)
3816  {
3817  util3d::adjustNormalsToViewPoint(cloud, viewPoint, (float)_ui->doubleSpinBox_groundNormalsUp->value());
3818  }
3819  }
3820  else
3821  {
3822  pcl::copyPointCloud(*cloudWithoutNormals, *cloud);
3823  }
3824  }
3825  else if(!_ui->checkBox_fromDepth->isChecked() && uContains(cachedScans, iter->first))
3826  {
3827  LaserScan scan = util3d::commonFiltering(cachedScans.at(iter->first),
3828  _ui->spinBox_decimation_scan->value(),
3829  _ui->doubleSpinBox_rangeMin->value(),
3830  _ui->doubleSpinBox_rangeMax->value(),
3831  _ui->doubleSpinBox_voxelSize_assembled->value(),
3832  _ui->spinBox_normalKSearch->value(),
3833  _ui->doubleSpinBox_normalRadiusSearch->value());
3834 
3835  if(!scan.empty())
3836  {
3837  scansHaveRGB = scan.hasRGB();
3838  }
3839  localTransform = scan.localTransform();
3840  cloud = util3d::laserScanToPointCloudRGBNormal(scan, localTransform); // put in base frame by default
3841  indices->resize(cloud->size());
3842  for(unsigned int i=0; i<indices->size(); ++i)
3843  {
3844  indices->at(i) = i;
3845  }
3846  }
3847  else
3848  {
3849  int weight = 0;
3850  if(cachedSignatures.contains(iter->first))
3851  {
3852  const Signature & s = cachedSignatures.find(iter->first).value();
3853  weight = s.getWeight();
3854  }
3855  else if(_dbDriver)
3856  {
3857  _dbDriver->getWeight(iter->first, weight);
3858  }
3859  if(weight>=0) // don't show error for intermediate nodes
3860  {
3861  _progressDialog->appendText(tr("Cached cloud %1 not found. You may want to regenerate the clouds (%2/%3).").arg(iter->first).arg(index).arg(poses.size()), Qt::darkYellow);
3862  }
3863  }
3864 
3865  if(_ui->checkBox_filtering->isChecked())
3866  {
3867  if(!indices->empty() &&
3868  (_ui->doubleSpinBox_ceilingHeight->value() != 0.0 ||
3869  _ui->doubleSpinBox_floorHeight->value() != 0.0))
3870  {
3871  float min = _ui->doubleSpinBox_floorHeight->value();
3872  float max = _ui->doubleSpinBox_ceilingHeight->value();
3873  indices = util3d::passThrough(
3874  util3d::transformPointCloud(cloud, iter->second),
3875  indices,
3876  "z",
3877  min!=0.0f&&(min<max || max==0.0f)?min:std::numeric_limits<int>::min(),
3878  max!=0.0f?max:std::numeric_limits<int>::max());
3879  }
3880  if(!indices->empty() &&
3881  ( _ui->doubleSpinBox_footprintHeight->value() != 0.0 &&
3882  _ui->doubleSpinBox_footprintWidth->value() != 0.0 &&
3883  _ui->doubleSpinBox_footprintLength->value() != 0.0))
3884  {
3885  // filter footprint
3886  float h = _ui->doubleSpinBox_footprintHeight->value();
3887  float w = _ui->doubleSpinBox_footprintWidth->value();
3888  float l = _ui->doubleSpinBox_footprintLength->value();
3889  indices = util3d::cropBox(
3890  cloud,
3891  indices,
3892  Eigen::Vector4f(
3893  -l/2.0f,
3894  -w/2.0f,
3895  h<0.0f?h:0,
3896  1),
3897  Eigen::Vector4f(
3898  l/2.0f,
3899  w/2.0f,
3900  h<0.0f?-h:h,
3901  1),
3903  true);
3904  }
3905 
3906  if( !indices->empty() &&
3907  _ui->doubleSpinBox_filteringRadius->value() > 0.0f &&
3908  _ui->spinBox_filteringMinNeighbors->value() > 0)
3909  {
3910  indices = util3d::radiusFiltering(cloud, indices, _ui->doubleSpinBox_filteringRadius->value(), _ui->spinBox_filteringMinNeighbors->value());
3911  if(indices->empty())
3912  {
3913  UWARN("Point cloud %d doesn't have anymore points (had %d points) after radius filtering.", iter->first, (int)cloud->size());
3914  }
3915  }
3916  }
3917 
3918  if(!indices->empty())
3919  {
3920  if((_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex()==2) && cloud->isOrganized())
3921  {
3922  cloud = util3d::transformPointCloud(cloud, localTransform.inverse()); // put back in camera frame
3923  }
3924  else if(_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex()==3)
3925  {
3926  cloud = util3d::transformPointCloud(cloud, localTransform.inverse()); // put back in scan frame
3927  }
3928 
3929  clouds.insert(std::make_pair(iter->first, std::make_pair(cloud, indices)));
3930  points = (int)cloud->size();
3931  totalIndices = (int)indices->size();
3932  }
3933  }
3934  else
3935  {
3936  UERROR("transform is null!?");
3937  }
3938 
3939  if(points>0)
3940  {
3941  if(_ui->checkBox_regenerate->isChecked())
3942  {
3943  _progressDialog->appendText(tr("Generated cloud %1 with %2 points and %3 indices (%4/%5).")
3944  .arg(iter->first).arg(points).arg(totalIndices).arg(index).arg(poses.size()));
3945  }
3946  else
3947  {
3948  _progressDialog->appendText(tr("Copied cloud %1 from cache with %2 points and %3 indices (%4/%5).")
3949  .arg(iter->first).arg(points).arg(totalIndices).arg(index).arg(poses.size()));
3950  }
3951  }
3952  else
3953  {
3954  _progressDialog->appendText(tr("Ignored cloud %1 (%2/%3).").arg(iter->first).arg(index).arg(poses.size()));
3955  }
3957  QApplication::processEvents();
3958  }
3959 
3960  return clouds;
3961 }
3962 
3963 
3965  const QString & workingDirectory,
3966  const std::map<int, Transform> & poses,
3967  const std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds,
3968  bool binaryMode,
3969  const std::vector<std::map<int, pcl::PointXY> > & pointToPixels)
3970 {
3971  if(clouds.size() == 1)
3972  {
3973 #ifdef RTABMAP_PDAL
3974  QString extensions = tr("Point cloud data (*.ply *.pcd");
3975  std::list<std::string> pdalFormats = uSplit(getPDALSupportedWriters(), ' ');
3976  for(std::list<std::string>::iterator iter=pdalFormats.begin(); iter!=pdalFormats.end(); ++iter)
3977  {
3978  if(iter->compare("ply") == 0 || iter->compare("pcd") == 0)
3979  {
3980  continue;
3981  }
3982  extensions += QString(" *.") + iter->c_str();
3983  }
3984  extensions += ")";
3985 #else
3986  QString extensions = tr("Point cloud data (*.ply *.pcd)");
3987 #endif
3988  QString path = QFileDialog::getSaveFileName(this, tr("Save cloud to ..."), workingDirectory+QDir::separator()+"cloud.ply", extensions);
3989 
3990  if(!path.isEmpty())
3991  {
3992  if(QFileInfo(path).suffix().isEmpty())
3993  {
3994  //use ply by default
3995  path += ".ply";
3996  }
3997 
3998  if(clouds.begin()->second->size())
3999  {
4000  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudRGBWithoutNormals;
4001  pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIWithoutNormals;
4002  pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloudIWithNormals;
4003  if(!_ui->checkBox_fromDepth->isChecked() && !_scansHaveRGB &&
4004  !(_ui->checkBox_cameraProjection->isEnabled() &&
4005  _ui->checkBox_cameraProjection->isChecked() &&
4006  _ui->checkBox_camProjRecolorPoints->isChecked() &&
4007  clouds.size()==1 && clouds.begin()->first==0))
4008  {
4009  // When laser scans are exported (and camera RGB was not applied), convert RGB to Intensity
4010  if(_ui->spinBox_normalKSearch->value()>0 || _ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
4011  {
4012  cloudIWithNormals.reset(new pcl::PointCloud<pcl::PointXYZINormal>);
4013  cloudIWithNormals->resize(clouds.begin()->second->size());
4014  for(unsigned int i=0; i<cloudIWithNormals->size(); ++i)
4015  {
4016  cloudIWithNormals->points[i].x = clouds.begin()->second->points[i].x;
4017  cloudIWithNormals->points[i].y = clouds.begin()->second->points[i].y;
4018  cloudIWithNormals->points[i].z = clouds.begin()->second->points[i].z;
4019  cloudIWithNormals->points[i].normal_x = clouds.begin()->second->points[i].normal_x;
4020  cloudIWithNormals->points[i].normal_y = clouds.begin()->second->points[i].normal_y;
4021  cloudIWithNormals->points[i].normal_z = clouds.begin()->second->points[i].normal_z;
4022  cloudIWithNormals->points[i].curvature = clouds.begin()->second->points[i].curvature;
4023  int * intensity = (int *)&cloudIWithNormals->points[i].intensity;
4024  *intensity =
4025  int(clouds.begin()->second->points[i].r) |
4026  int(clouds.begin()->second->points[i].g) << 8 |
4027  int(clouds.begin()->second->points[i].b) << 16 |
4028  int(clouds.begin()->second->points[i].a) << 24;
4029  }
4030  }
4031  else
4032  {
4033  cloudIWithoutNormals.reset(new pcl::PointCloud<pcl::PointXYZI>);
4034  cloudIWithoutNormals->resize(clouds.begin()->second->size());
4035  for(unsigned int i=0; i<cloudIWithoutNormals->size(); ++i)
4036  {
4037  cloudIWithoutNormals->points[i].x = clouds.begin()->second->points[i].x;
4038  cloudIWithoutNormals->points[i].y = clouds.begin()->second->points[i].y;
4039  cloudIWithoutNormals->points[i].z = clouds.begin()->second->points[i].z;
4040  int * intensity = (int *)&cloudIWithoutNormals->points[i].intensity;
4041  *intensity =
4042  int(clouds.begin()->second->points[i].r) |
4043  int(clouds.begin()->second->points[i].g) << 8 |
4044  int(clouds.begin()->second->points[i].b) << 16 |
4045  int(clouds.begin()->second->points[i].a) << 24;
4046  }
4047  }
4048  }
4049  else if(_ui->spinBox_normalKSearch->value()<=0 && _ui->doubleSpinBox_normalRadiusSearch->value()<=0.0)
4050  {
4051  cloudRGBWithoutNormals.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
4052  pcl::copyPointCloud(*clouds.begin()->second, *cloudRGBWithoutNormals);
4053  }
4054 
4055  _progressDialog->appendText(tr("Saving the cloud (%1 points)...").arg(clouds.begin()->second->size()));
4056 
4057  bool success =false;
4058  if(QFileInfo(path).suffix() == "pcd")
4059  {
4060  if(cloudIWithNormals.get())
4061  {
4062  success = pcl::io::savePCDFile(path.toStdString(), *cloudIWithNormals, binaryMode) == 0;
4063  }
4064  else if(cloudIWithoutNormals.get())
4065  {
4066  success = pcl::io::savePCDFile(path.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
4067  }
4068  else if(cloudRGBWithoutNormals.get())
4069  {
4070  success = pcl::io::savePCDFile(path.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
4071  }
4072  else
4073  {
4074  success = pcl::io::savePCDFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
4075  }
4076  }
4077 #ifdef RTABMAP_PDAL
4078  else if(QFileInfo(path).suffix() == "ply" && pointToPixels.empty()) {
4079 #else
4080  else if(QFileInfo(path).suffix() == "ply") {
4081 #endif
4082  if(cloudIWithNormals.get())
4083  {
4084  success = pcl::io::savePLYFile(path.toStdString(), *cloudIWithNormals, binaryMode) == 0;
4085  }
4086  else if(cloudIWithoutNormals.get())
4087  {
4088  success = pcl::io::savePLYFile(path.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
4089  }
4090  else if(cloudRGBWithoutNormals.get())
4091  {
4092  success = pcl::io::savePLYFile(path.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
4093  }
4094  else
4095  {
4096  success = pcl::io::savePLYFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
4097  }
4098  }
4099 #ifdef RTABMAP_PDAL
4100  else if(!QFileInfo(path).suffix().isEmpty())
4101  {
4102  std::vector<int> cameraIds(pointToPixels.size(), 0);
4103  for(size_t i=0;i<pointToPixels.size(); ++i)
4104  {
4105  if(!pointToPixels[i].empty())
4106  {
4107  cameraIds[i] = pointToPixels[i].begin()->first;
4108  }
4109  }
4110  if(cloudIWithNormals.get())
4111  {
4112  success = savePDALFile(path.toStdString(), *cloudIWithNormals, cameraIds, binaryMode) == 0;
4113  }
4114  else if(cloudIWithoutNormals.get())
4115  {
4116  success = savePDALFile(path.toStdString(), *cloudIWithoutNormals, cameraIds, binaryMode) == 0;
4117  }
4118  else if(cloudRGBWithoutNormals.get())
4119  {
4120  success = savePDALFile(path.toStdString(), *cloudRGBWithoutNormals, cameraIds, binaryMode) == 0;
4121  }
4122  else
4123  {
4124  success = savePDALFile(path.toStdString(), *clouds.begin()->second, cameraIds, binaryMode) == 0;
4125  }
4126  }
4127 #endif
4128  else
4129  {
4130  UERROR("Extension not recognized! (%s) Should be one of (*.ply *.pcd *.las).", QFileInfo(path).suffix().toStdString().c_str());
4131  }
4132  if(success)
4133  {
4135  _progressDialog->appendText(tr("Saving the cloud (%1 points)... done.").arg(clouds.begin()->second->size()));
4136 
4137  QMessageBox::information(this, tr("Save successful!"), tr("Cloud saved to \"%1\"").arg(path));
4138  }
4139  else
4140  {
4141  QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
4142  }
4143  }
4144  else
4145  {
4146  QMessageBox::warning(this, tr("Save failed!"), tr("Cloud is empty..."));
4147  }
4148  }
4149  }
4150  else if(clouds.size())
4151  {
4152  QStringList items;
4153  items.push_back("ply");
4154  items.push_back("pcd");
4155 #ifdef RTABMAP_PDAL
4156  QString extensions = tr("Save clouds to (*.ply *.pcd");
4157  std::list<std::string> pdalFormats = uSplit(getPDALSupportedWriters(), ' ');
4158  for(std::list<std::string>::iterator iter=pdalFormats.begin(); iter!=pdalFormats.end(); ++iter)
4159  {
4160  if(iter->compare("ply") == 0 || iter->compare("pcd") == 0)
4161  {
4162  continue;
4163  }
4164  extensions += QString(" *.") + iter->c_str();
4165 
4166  items.push_back(iter->c_str());
4167  }
4168  extensions += ")...";
4169 #else
4170  QString extensions = tr("Save clouds to (*.ply *.pcd)...");
4171 #endif
4172  QString path = QFileDialog::getExistingDirectory(this, extensions, workingDirectory, 0);
4173  if(!path.isEmpty())
4174  {
4175  bool ok = false;
4176  QString suffix = QInputDialog::getItem(this, tr("File format"), tr("Which format?"), items, 0, false, &ok);
4177 
4178  if(ok)
4179  {
4180  QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "cloud", &ok);
4181 
4182  if(ok)
4183  {
4184  for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::const_iterator iter=clouds.begin(); iter!=clouds.end(); ++iter)
4185  {
4186  if(iter->second->size())
4187  {
4188  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformedCloud;
4189  transformedCloud = util3d::transformPointCloud(iter->second, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
4190 
4191  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudRGBWithoutNormals;
4192  pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIWithoutNormals;
4193  pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloudIWithNormals;
4194  if(!_ui->checkBox_fromDepth->isChecked() && !_scansHaveRGB)
4195  {
4196  // When laser scans are exported, convert RGB to Intensity
4197  if(_ui->spinBox_normalKSearch->value()>0 || _ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
4198  {
4199  cloudIWithNormals.reset(new pcl::PointCloud<pcl::PointXYZINormal>);
4200  cloudIWithNormals->resize(transformedCloud->size());
4201  for(unsigned int i=0; i<cloudIWithNormals->size(); ++i)
4202  {
4203  cloudIWithNormals->points[i].x = transformedCloud->points[i].x;
4204  cloudIWithNormals->points[i].y = transformedCloud->points[i].y;
4205  cloudIWithNormals->points[i].z = transformedCloud->points[i].z;
4206  cloudIWithNormals->points[i].normal_x = transformedCloud->points[i].normal_x;
4207  cloudIWithNormals->points[i].normal_y = transformedCloud->points[i].normal_y;
4208  cloudIWithNormals->points[i].normal_z = transformedCloud->points[i].normal_z;
4209  cloudIWithNormals->points[i].curvature = transformedCloud->points[i].curvature;
4210  int * intensity = (int *)&cloudIWithNormals->points[i].intensity;
4211  *intensity =
4212  int(transformedCloud->points[i].r) |
4213  int(transformedCloud->points[i].g) << 8 |
4214  int(transformedCloud->points[i].b) << 16 |
4215  int(transformedCloud->points[i].a) << 24;
4216  }
4217  }
4218  else
4219  {
4220  cloudIWithoutNormals.reset(new pcl::PointCloud<pcl::PointXYZI>);
4221  cloudIWithoutNormals->resize(transformedCloud->size());
4222  for(unsigned int i=0; i<cloudIWithoutNormals->size(); ++i)
4223  {
4224  cloudIWithoutNormals->points[i].x = transformedCloud->points[i].x;
4225  cloudIWithoutNormals->points[i].y = transformedCloud->points[i].y;
4226  cloudIWithoutNormals->points[i].z = transformedCloud->points[i].z;
4227  int * intensity = (int *)&cloudIWithoutNormals->points[i].intensity;
4228  *intensity =
4229  int(transformedCloud->points[i].r) |
4230  int(transformedCloud->points[i].g) << 8 |
4231  int(transformedCloud->points[i].b) << 16 |
4232  int(transformedCloud->points[i].a) << 24;
4233  }
4234  }
4235  }
4236  else if(_ui->spinBox_normalKSearch->value()<=0 && _ui->doubleSpinBox_normalRadiusSearch->value()<=0.0)
4237  {
4238  cloudRGBWithoutNormals.reset(new pcl::PointCloud<pcl::PointXYZRGB>);
4239  pcl::copyPointCloud(*transformedCloud, *cloudRGBWithoutNormals);
4240  }
4241 
4242  QString pathFile = path+QDir::separator()+QString("%1%2.%3").arg(prefix).arg(iter->first).arg(suffix);
4243  bool success =false;
4244  if(suffix == "pcd")
4245  {
4246  if(cloudIWithNormals.get())
4247  {
4248  success = pcl::io::savePCDFile(pathFile.toStdString(), *cloudIWithNormals, binaryMode) == 0;
4249  }
4250  else if(cloudIWithoutNormals.get())
4251  {
4252  success = pcl::io::savePCDFile(pathFile.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
4253  }
4254  else if(cloudRGBWithoutNormals.get())
4255  {
4256  success = pcl::io::savePCDFile(pathFile.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
4257  }
4258  else
4259  {
4260  success = pcl::io::savePCDFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
4261  }
4262  }
4263  else if(suffix == "ply")
4264  {
4265  if(cloudIWithNormals.get())
4266  {
4267  success = pcl::io::savePLYFile(pathFile.toStdString(), *cloudIWithNormals, binaryMode) == 0;
4268  }
4269  else if(cloudIWithoutNormals.get())
4270  {
4271  success = pcl::io::savePLYFile(pathFile.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
4272  }
4273  else if(cloudRGBWithoutNormals.get())
4274  {
4275  success = pcl::io::savePLYFile(pathFile.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
4276  }
4277  else
4278  {
4279  success = pcl::io::savePLYFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
4280  }
4281  }
4282 #ifdef RTABMAP_PDAL
4283  else if(!suffix.isEmpty())
4284  {
4285  if(cloudIWithNormals.get())
4286  {
4287  success = savePDALFile(pathFile.toStdString(), *cloudIWithNormals) == 0;
4288  }
4289  else if(cloudIWithoutNormals.get())
4290  {
4291  success = savePDALFile(pathFile.toStdString(), *cloudIWithoutNormals) == 0;
4292  }
4293  else if(cloudRGBWithoutNormals.get())
4294  {
4295  success = savePDALFile(pathFile.toStdString(), *cloudRGBWithoutNormals) == 0;
4296  }
4297  else
4298  {
4299  success = savePDALFile(pathFile.toStdString(), *transformedCloud) == 0;
4300  }
4301  }
4302 #endif
4303  else
4304  {
4305  UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
4306  }
4307  if(success)
4308  {
4309  _progressDialog->appendText(tr("Saved cloud %1 (%2 points) to %3.").arg(iter->first).arg(iter->second->size()).arg(pathFile));
4310  }
4311  else
4312  {
4313  _progressDialog->appendText(tr("Failed saving cloud %1 (%2 points) to %3.").arg(iter->first).arg(iter->second->size()).arg(pathFile), Qt::darkRed);
4314  _progressDialog->setAutoClose(false);
4315  }
4316  }
4317  else
4318  {
4319  _progressDialog->appendText(tr("Cloud %1 is empty!").arg(iter->first));
4320  }
4322  QApplication::processEvents();
4323  if(_canceled)
4324  {
4325  return;
4326  }
4327  }
4328  }
4329  }
4330  }
4331  }
4332 }
4333 
4335  const QString & workingDirectory,
4336  const std::map<int, Transform> & poses,
4337  const std::map<int, pcl::PolygonMesh::Ptr> & meshes,
4338  bool binaryMode)
4339 {
4340  if(meshes.size() == 1)
4341  {
4342  QString path = QFileDialog::getSaveFileName(this, tr("Save mesh to ..."), workingDirectory+QDir::separator()+"mesh.ply", tr("Mesh (*.ply)"));
4343  if(!path.isEmpty())
4344  {
4345  if(meshes.begin()->second->polygons.size())
4346  {
4347  _progressDialog->appendText(tr("Saving the mesh (%1 polygons)...").arg(meshes.begin()->second->polygons.size()));
4348  QApplication::processEvents();
4349  uSleep(100);
4350  QApplication::processEvents();
4351 
4352  bool success =false;
4353  if(QFileInfo(path).suffix() == "")
4354  {
4355  path += ".ply";
4356  }
4357 
4358  if(QFileInfo(path).suffix() == "ply")
4359  {
4360  if(binaryMode)
4361  {
4362  success = pcl::io::savePLYFileBinary(path.toStdString(), *meshes.begin()->second) == 0;
4363  }
4364  else
4365  {
4366  success = pcl::io::savePLYFile(path.toStdString(), *meshes.begin()->second) == 0;
4367  }
4368  }
4369  else if(QFileInfo(path).suffix() == "obj")
4370  {
4371  success = pcl::io::saveOBJFile(path.toStdString(), *meshes.begin()->second) == 0;
4372  }
4373  else
4374  {
4375  UERROR("Extension not recognized! (%s) Should be (*.ply).", QFileInfo(path).suffix().toStdString().c_str());
4376  }
4377  if(success)
4378  {
4380  _progressDialog->appendText(tr("Saving the mesh (%1 polygons)... done.").arg(meshes.begin()->second->polygons.size()));
4381 
4382  QMessageBox::information(this, tr("Save successful!"), tr("Mesh saved to \"%1\"").arg(path));
4383  }
4384  else
4385  {
4386  QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
4387  }
4388  }
4389  else
4390  {
4391  QMessageBox::warning(this, tr("Save failed!"), tr("Cloud is empty..."));
4392  }
4393  }
4394  }
4395  else if(meshes.size())
4396  {
4397  QString path = QFileDialog::getExistingDirectory(this, tr("Save meshes to (*.ply *.obj)..."), workingDirectory, 0);
4398  if(!path.isEmpty())
4399  {
4400  bool ok = false;
4401  QStringList items;
4402  items.push_back("ply");
4403  items.push_back("obj");
4404  QString suffix = QInputDialog::getItem(this, tr("File format"), tr("Which format?"), items, 0, false, &ok);
4405 
4406  if(ok)
4407  {
4408  QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "mesh", &ok);
4409 
4410  if(ok)
4411  {
4412  for(std::map<int, pcl::PolygonMesh::Ptr>::const_iterator iter=meshes.begin(); iter!=meshes.end(); ++iter)
4413  {
4414  if(iter->second->polygons.size())
4415  {
4416  pcl::PolygonMesh mesh;
4417  mesh.polygons = iter->second->polygons;
4418  bool isRGB = false;
4419  for(unsigned int i=0; i<iter->second->cloud.fields.size(); ++i)
4420  {
4421  if(iter->second->cloud.fields[i].name.compare("rgb") == 0)
4422  {
4423  isRGB=true;
4424  break;
4425  }
4426  }
4427  if(isRGB)
4428  {
4429  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZRGB>);
4430  pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
4431  tmp = util3d::transformPointCloud(tmp, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
4432  pcl::toPCLPointCloud2(*tmp, mesh.cloud);
4433  }
4434  else
4435  {
4436  pcl::PointCloud<pcl::PointXYZ>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZ>);
4437  pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
4438  tmp = util3d::transformPointCloud(tmp, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
4439  pcl::toPCLPointCloud2(*tmp, mesh.cloud);
4440  }
4441 
4442  QString pathFile = path+QDir::separator()+QString("%1%2.%3").arg(prefix).arg(iter->first).arg(suffix);
4443  bool success =false;
4444  if(suffix == "ply")
4445  {
4446  if(binaryMode)
4447  {
4448  success = pcl::io::savePLYFileBinary(pathFile.toStdString(), mesh) == 0;
4449  }
4450  else
4451  {
4452  success = pcl::io::savePLYFile(pathFile.toStdString(), mesh) == 0;
4453  }
4454  }
4455  else if(suffix == "obj")
4456  {
4457  success = pcl::io::saveOBJFile(pathFile.toStdString(), mesh) == 0;
4458  }
4459  else
4460  {
4461  UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
4462  }
4463  if(success)
4464  {
4465  _progressDialog->appendText(tr("Saved mesh %1 (%2 polygons) to %3.")
4466  .arg(iter->first).arg(iter->second->polygons.size()).arg(pathFile));
4467  }
4468  else
4469  {
4470  _progressDialog->appendText(tr("Failed saving mesh %1 (%2 polygons) to %3.")
4471  .arg(iter->first).arg(iter->second->polygons.size()).arg(pathFile), Qt::darkRed);
4472  _progressDialog->setAutoClose(false);
4473  }
4474  }
4475  else
4476  {
4477  _progressDialog->appendText(tr("Mesh %1 is empty!").arg(iter->first));
4478  }
4480  QApplication::processEvents();
4481  if(_canceled)
4482  {
4483  return;
4484  }
4485  }
4486  }
4487  }
4488  }
4489  }
4490 }
4491 
4493  const QString & workingDirectory,
4494  const std::map<int, Transform> & poses,
4495  std::map<int, pcl::TextureMesh::Ptr> & meshes,
4496  const QMap<int, Signature> & cachedSignatures,
4497  const std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels)
4498 {
4499  std::map<int, cv::Mat> images;
4500  std::map<int, std::vector<CameraModel> > calibrations;
4501  for(QMap<int, Signature>::const_iterator iter=cachedSignatures.constBegin(); iter!=cachedSignatures.constEnd(); ++iter)
4502  {
4503  std::vector<CameraModel> models;
4504  if(iter->sensorData().cameraModels().size())
4505  {
4506  models = iter->sensorData().cameraModels();
4507  }
4508  else if(iter->sensorData().stereoCameraModels().size())
4509  {
4510  for(size_t i=0; i<iter->sensorData().stereoCameraModels().size(); ++i)
4511  {
4512  models.push_back(iter->sensorData().stereoCameraModels()[i].left());
4513  }
4514  }
4515 
4516  if(!models.empty())
4517  {
4518  if(!iter->sensorData().imageRaw().empty())
4519  {
4520  calibrations.insert(std::make_pair(iter.key(), models));
4521  images.insert(std::make_pair(iter.key(), iter->sensorData().imageRaw()));
4522  }
4523  else if(!iter->sensorData().imageCompressed().empty())
4524  {
4525  calibrations.insert(std::make_pair(iter.key(), models));
4526  images.insert(std::make_pair(iter.key(), iter->sensorData().imageCompressed()));
4527  }
4528  }
4529  }
4530  int textureSize = 1024;
4531  if(_ui->comboBox_meshingTextureSize->currentIndex() > 0)
4532  {
4533  textureSize = 128 << _ui->comboBox_meshingTextureSize->currentIndex(); // start at 256
4534  }
4535  int blendingDecimation = 0;
4536  if(_ui->checkBox_blending->isChecked())
4537  {
4538  if(_ui->comboBox_blendingDecimation->currentIndex() > 0)
4539  {
4540  blendingDecimation = 1 << (_ui->comboBox_blendingDecimation->currentIndex()-1);
4541  }
4542  }
4543 
4544  if(meshes.size() == 1)
4545  {
4546  QString path = QFileDialog::getSaveFileName(this, tr("Save texture mesh to ..."), workingDirectory+QDir::separator()+"mesh.obj", tr("Mesh (*.obj)"));
4547  if(!path.isEmpty())
4548  {
4549  if(meshes.begin()->second->tex_materials.size())
4550  {
4551  _progressDialog->appendText(tr("Saving the mesh (with %1 textures)...").arg(meshes.begin()->second->tex_materials.size()));
4552  QApplication::processEvents();
4553  uSleep(100);
4554  QApplication::processEvents();
4555 
4556  bool success =false;
4557  if(QFileInfo(path).suffix() == "")
4558  {
4559  path += ".obj";
4560  }
4561 
4562  pcl::TextureMesh::Ptr mesh = meshes.begin()->second;
4563 
4564  cv::Mat globalTextures;
4565  bool texturesMerged = _ui->comboBox_meshingTextureSize->isEnabled() && _ui->comboBox_meshingTextureSize->currentIndex() > 0;
4566  if(texturesMerged && mesh->tex_materials.size()>1)
4567  {
4568  _progressDialog->appendText(tr("Merging textures..."));
4569  QApplication::processEvents();
4570  uSleep(100);
4571  QApplication::processEvents();
4572 
4573  std::map<int, std::map<int, cv::Vec4d> > gains;
4574  std::map<int, std::map<int, cv::Mat> > blendingGains;
4575  std::pair<float, float> contrastValues(0,0);
4576  globalTextures = util3d::mergeTextures(
4577  *mesh,
4578  images,
4579  calibrations,
4580  0,
4581  _dbDriver,
4582  textureSize,
4583  _ui->checkBox_multiband->isEnabled() && _ui->checkBox_multiband->isChecked()?1:_ui->spinBox_mesh_maxTextures->value(),
4584  textureVertexToPixels,
4585  _ui->checkBox_gainCompensation->isChecked(),
4586  _ui->doubleSpinBox_gainBeta->value(),
4587  _ui->checkBox_gainRGB->isChecked(),
4588  _ui->checkBox_blending->isChecked(),
4589  blendingDecimation,
4590  _ui->spinBox_textureBrightnessContrastRatioLow->value(),
4591  _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
4592  _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked(),
4593  0,
4594  0,
4595  &gains,
4596  &blendingGains,
4597  &contrastValues);
4598 
4599  _progressDialog->appendText(tr("Merging textures... done."));
4600  QApplication::processEvents();
4601  uSleep(100);
4602  QApplication::processEvents();
4603 
4604  if(_ui->checkBox_multiband->isEnabled() && _ui->checkBox_multiband->isChecked() && mesh->tex_polygons.size() == 1)
4605  {
4606  _progressDialog->appendText(tr("Multiband texturing... (this may take a couple of minutes!)"));
4607  QApplication::processEvents();
4608  uSleep(100);
4609  QApplication::processEvents();
4610 
4611  success = util3d::multiBandTexturing(
4612  path.toStdString(),
4613  mesh->cloud,
4614  mesh->tex_polygons[0],
4615  poses,
4616  textureVertexToPixels,
4617  images,
4618  calibrations,
4619  0,
4620  _dbDriver,
4621  textureSize,
4622  _ui->spinBox_multiband_downscale->value(),
4623  _ui->lineEdit_multiband_nbcontrib->text().toStdString(),
4624  _ui->comboBox_meshingTextureFormat->currentText().toStdString(),
4625  gains,
4626  blendingGains,
4627  contrastValues,
4628  true,
4629  _ui->comboBox_multiband_unwrap->currentIndex(),
4630  _ui->checkBox_multiband_fillholes->isChecked(),
4631  _ui->spinBox_multiband_padding->value(),
4632  _ui->doubleSpinBox_multiband_bestscore->value(),
4633  _ui->doubleSpinBox_multiband_angle->value(),
4634  _ui->checkBox_multiband_forcevisible->isChecked());
4635  if(success)
4636  {
4638  _progressDialog->appendText(tr("Saving the mesh... done."));
4639 
4640  QMessageBox::information(this, tr("Save successful!"), tr("Mesh saved to \"%1\"").arg(path));
4641  }
4642  else
4643  {
4644  QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
4645  }
4646  return;
4647  }
4648  }
4649 
4650  bool singleTexture = mesh->tex_materials.size() == 1;
4651  if(!singleTexture)
4652  {
4653  removeDirRecursively(QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName());
4654  QDir(QFileInfo(path).absoluteDir().absolutePath()).mkdir(QFileInfo(path).baseName());
4655  }
4656 
4657  // used for multi camera texturing, to avoid reloading same texture for sub cameras
4658  cv::Mat previousImage;
4659  int previousTextureId = 0;
4660  std::vector<CameraModel> previousCameraModels;
4661 
4662  cv::Size imageSize;
4663  for(unsigned int i=0; i<mesh->tex_materials.size(); ++i)
4664  {
4665  if(!mesh->tex_materials[i].tex_file.empty())
4666  {
4667  // absolute path
4668  QString fullPath;
4669  if(singleTexture)
4670  {
4671  fullPath = QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName()+_ui->comboBox_meshingTextureFormat->currentText();
4672  }
4673  else
4674  {
4675  fullPath = QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName()+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText();
4676  }
4677  UDEBUG("Saving %s...", fullPath.toStdString().c_str());
4678  if(singleTexture || !QFileInfo(fullPath).exists())
4679  {
4680  std::list<std::string> texFileSplit = uSplit(mesh->tex_materials[i].tex_file, '_');
4681  if(texFileSplit.size() && uIsInteger(texFileSplit.front(), false))
4682  {
4683  int textureId = uStr2Int(texFileSplit.front());
4684  int textureSubCamera = -1;
4685  if(texFileSplit.size() == 2 &&
4686  uIsInteger(texFileSplit.back(), false))
4687  {
4688  textureSubCamera = uStr2Int(texFileSplit.back());
4689  }
4690  cv::Mat image;
4691  std::vector<CameraModel> cameraModels;
4692 
4693  if(textureId == previousTextureId)
4694  {
4695  image = previousImage;
4696  cameraModels = previousCameraModels;
4697  }
4698  else
4699  {
4700  if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
4701  {
4702  cachedSignatures.value(textureId).sensorData().uncompressDataConst(&image, 0);
4703  cameraModels = cachedSignatures.value(textureId).sensorData().cameraModels();
4704  }
4705  else if(_dbDriver)
4706  {
4707  SensorData data;
4708  _dbDriver->getNodeData(textureId, data, true, false, false, false);
4709  data.uncompressDataConst(&image, 0);
4710  std::vector<StereoCameraModel> stereoModels;
4711  _dbDriver->getCalibration(textureId, cameraModels, stereoModels);
4712  if(cameraModels.empty())
4713  {
4714  for(size_t i=0; i<stereoModels.size(); ++i)
4715  {
4716  cameraModels.push_back(stereoModels[i].left());
4717  }
4718  }
4719  }
4720 
4721  previousImage = image;
4722  previousCameraModels = cameraModels;
4723  previousTextureId = textureId;
4724  }
4725  UASSERT(!image.empty());
4726  imageSize = image.size();
4727  if(textureSubCamera>=0)
4728  {
4729  UASSERT(cameraModels.size());
4730  imageSize.width/=cameraModels.size();
4731  image = image.colRange(imageSize.width*textureSubCamera, imageSize.width*(textureSubCamera+1));
4732  }
4733  if(_ui->checkBox_gainCompensation->isChecked() && _compensator && _compensator->getIndex(textureId) >= 0)
4734  {
4735  _compensator->apply(textureId, image, _ui->checkBox_gainRGB->isChecked());
4736  }
4737 
4738  if(!cv::imwrite(fullPath.toStdString(), image))
4739  {
4740  _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
4741  .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
4742  _progressDialog->setAutoClose(false);
4743  }
4744  }
4745  else if(imageSize.height && imageSize.width)
4746  {
4747  // make a blank texture
4748  cv::Mat image = cv::Mat::ones(imageSize, CV_8UC1)*255;
4749  cv::imwrite(fullPath.toStdString(), image);
4750  }
4751  else if(!globalTextures.empty())
4752  {
4753  if(!cv::imwrite(fullPath.toStdString(), globalTextures(cv::Range::all(), cv::Range(i*globalTextures.rows, (i+1)*globalTextures.rows))))
4754  {
4755  _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
4756  .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
4757  _progressDialog->setAutoClose(false);
4758  }
4759  }
4760  else
4761  {
4762  UWARN("Ignored texture %s (no image size set yet)", mesh->tex_materials[i].tex_file.c_str());
4763  }
4764  }
4765  else
4766  {
4767  UWARN("File %s already exists!", fullPath.toStdString().c_str());
4768  }
4769  // relative path
4770  if(singleTexture)
4771  {
4772  mesh->tex_materials[i].tex_file=QFileInfo(path).baseName().toStdString()+_ui->comboBox_meshingTextureFormat->currentText().toStdString();
4773  }
4774  else
4775  {
4776  mesh->tex_materials[i].tex_file=(QFileInfo(path).baseName()+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
4777  }
4778  }
4779  }
4780 
4781  success = pcl::io::saveOBJFile(path.toStdString(), *mesh) == 0;
4782  if(success)
4783  {
4785  _progressDialog->appendText(tr("Saving the mesh (with %1 textures)... done.").arg(mesh->tex_materials.size()));
4786 
4787  QMessageBox::information(this, tr("Save successful!"), tr("Mesh saved to \"%1\"").arg(path));
4788  }
4789  else
4790  {
4791  QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
4792  }
4793  }
4794  else
4795  {
4796  QMessageBox::warning(this, tr("Save failed!"), tr("No textures..."));
4797  }
4798  }
4799  }
4800  else if(meshes.size())
4801  {
4802  QString path = QFileDialog::getExistingDirectory(this, tr("Save texture meshes to (*.obj)..."), workingDirectory, 0);
4803  if(!path.isEmpty())
4804  {
4805  bool ok = false;
4806  QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "mesh", &ok);
4807  QString suffix = "obj";
4808 
4809  if(ok)
4810  {
4811  for(std::map<int, pcl::TextureMesh::Ptr>::iterator iter=meshes.begin(); iter!=meshes.end(); ++iter)
4812  {
4813  QString currentPrefix=prefix+QString::number(iter->first);
4814  if(iter->second->tex_materials.size())
4815  {
4816  pcl::TextureMesh::Ptr mesh = iter->second;
4817  cv::Mat globalTextures;
4818  bool texturesMerged = _ui->comboBox_meshingTextureSize->isEnabled() && _ui->comboBox_meshingTextureSize->currentIndex() > 0;
4819  if(texturesMerged && mesh->tex_materials.size()>1)
4820  {
4821  globalTextures = util3d::mergeTextures(
4822  *mesh,
4823  images,
4824  calibrations,
4825  0,
4826  _dbDriver,
4827  textureSize,
4828  _ui->spinBox_mesh_maxTextures->value(),
4829  textureVertexToPixels,
4830  _ui->checkBox_gainCompensation->isChecked(),
4831  _ui->doubleSpinBox_gainBeta->value(),
4832  _ui->checkBox_gainRGB->isChecked(),
4833  _ui->checkBox_blending->isChecked(),
4834  blendingDecimation,
4835  _ui->spinBox_textureBrightnessContrastRatioLow->value(),
4836  _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
4837  _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked());
4838  }
4839  bool singleTexture = mesh->tex_materials.size() == 1;
4840  if(!singleTexture)
4841  {
4842  removeDirRecursively(path+QDir::separator()+currentPrefix);
4843  QDir(path).mkdir(currentPrefix);
4844  }
4845 
4846  // used for multi camera texturing, to avoid reloading same texture for sub cameras
4847  cv::Mat previousImage;
4848  int previousTextureId = 0;
4849  std::vector<CameraModel> previousCameraModels;
4850 
4851  cv::Size imageSize;
4852  for(unsigned int i=0;i<mesh->tex_materials.size(); ++i)
4853  {
4854  if(!mesh->tex_materials[i].tex_file.empty())
4855  {
4856  std::list<std::string> texFileSplit = uSplit(mesh->tex_materials[i].tex_file, '_');
4857  int textureId = 0;
4858  int textureSubCamera = -1;
4859  if(texFileSplit.size() && uIsInteger(texFileSplit.front(), false))
4860  {
4861  textureId = uStr2Int(texFileSplit.front());
4862  if(texFileSplit.size() == 2 &&
4863  uIsInteger(texFileSplit.back(), false))
4864  {
4865  textureSubCamera = uStr2Int(texFileSplit.back());
4866  }
4867  }
4868 
4869  // absolute path
4870  QString fullPath;
4871  if(singleTexture)
4872  {
4873  mesh->tex_materials[i].tex_file = uNumber2Str(iter->first);
4874  fullPath = path+QDir::separator()+prefix + QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText();
4875  }
4876  else
4877  {
4878  fullPath = path+QDir::separator()+currentPrefix+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText();
4879  }
4880  if(textureId>0)
4881  {
4882  cv::Mat image;
4883  std::vector<CameraModel> cameraModels;
4884 
4885  if(textureId == previousTextureId)
4886  {
4887  image = previousImage;
4888  cameraModels = previousCameraModels;
4889  }
4890  else
4891  {
4892  if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
4893  {
4894  cachedSignatures.value(textureId).sensorData().uncompressDataConst(&image, 0);
4895  cameraModels = cachedSignatures.value(textureId).sensorData().cameraModels();
4896  }
4897  else if(_dbDriver)
4898  {
4899  SensorData data;
4900  _dbDriver->getNodeData(textureId, data, true, false, false, false);
4901  data.uncompressDataConst(&image, 0);
4902  std::vector<StereoCameraModel> stereoModels;
4903  _dbDriver->getCalibration(textureId, cameraModels, stereoModels);
4904  if(cameraModels.empty())
4905  {
4906  for(size_t i=0; i<stereoModels.size(); ++i)
4907  {
4908  cameraModels.push_back(stereoModels[i].left());
4909  }
4910  }
4911  }
4912 
4913  previousImage = image;
4914  previousCameraModels = cameraModels;
4915  previousTextureId = textureId;
4916  }
4917 
4918 
4919  UASSERT(!image.empty());
4920  imageSize = image.size();
4921  if(textureSubCamera>=0)
4922  {
4923  UASSERT(cameraModels.size());
4924  imageSize.width/=cameraModels.size();
4925  image = image.colRange(imageSize.width*textureSubCamera, imageSize.width*(textureSubCamera+1));
4926  }
4927  if(_ui->checkBox_gainCompensation->isChecked() && _compensator && _compensator->getIndex(textureId) >= 0)
4928  {
4929  _compensator->apply(textureId, image, _ui->checkBox_gainRGB->isChecked());
4930  }
4931 
4932  if(!cv::imwrite(fullPath.toStdString(), image))
4933  {
4934  _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
4935  .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
4936  _progressDialog->setAutoClose(false);
4937  }
4938  }
4939  else if(imageSize.height && imageSize.width)
4940  {
4941  // make a blank texture
4942  cv::Mat image = cv::Mat::ones(imageSize, CV_8UC1)*255;
4943  cv::imwrite(fullPath.toStdString(), image);
4944  }
4945  else if(!globalTextures.empty())
4946  {
4947  if(!cv::imwrite(fullPath.toStdString(), globalTextures(cv::Range::all(), cv::Range(i*globalTextures.rows, (i+1)*globalTextures.rows))))
4948  {
4949  _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
4950  .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
4951  _progressDialog->setAutoClose(false);
4952  }
4953  }
4954  else
4955  {
4956  UWARN("Ignored texture %s (no image size set yet)", mesh->tex_materials[i].tex_file.c_str());
4957  }
4958  // relative path
4959  if(singleTexture)
4960  {
4961  mesh->tex_materials[i].tex_file=(prefix+ QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
4962  }
4963  else
4964  {
4965  mesh->tex_materials[i].tex_file=(currentPrefix+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
4966  }
4967  }
4968  }
4969  pcl::PointCloud<pcl::PointNormal>::Ptr tmp(new pcl::PointCloud<pcl::PointNormal>);
4970  pcl::fromPCLPointCloud2(mesh->cloud, *tmp);
4971  tmp = util3d::transformPointCloud(tmp, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
4972  pcl::toPCLPointCloud2(*tmp, mesh->cloud);
4973 
4974  QString pathFile = path+QDir::separator()+QString("%1.%3").arg(currentPrefix).arg(suffix);
4975  bool success =false;
4976  if(suffix == "obj")
4977  {
4978  success = pcl::io::saveOBJFile(pathFile.toStdString(), *mesh) == 0;
4979  }
4980  else
4981  {
4982  UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
4983  }
4984  if(success)
4985  {
4986  _progressDialog->appendText(tr("Saved mesh %1 (%2 textures) to %3.")
4987  .arg(iter->first).arg(mesh->tex_materials.size()).arg(pathFile));
4988  }
4989  else
4990  {
4991  _progressDialog->appendText(tr("Failed saving mesh %1 (%2 textures) to %3.")
4992  .arg(iter->first).arg(mesh->tex_materials.size()).arg(pathFile), Qt::darkRed);
4993  _progressDialog->setAutoClose(false);
4994  }
4995  }
4996  else
4997  {
4998  _progressDialog->appendText(tr("Mesh %1 is empty!").arg(iter->first));
4999  }
5001  QApplication::processEvents();
5002  if(_canceled)
5003  {
5004  return;
5005  }
5006  }
5007  }
5008  }
5009  }
5010 }
5011 
5012 }
bool uIsInteger(const std::string &str, bool checkForSign=true)
Definition: UStl.h:632
void setDefaultBackgroundColor(const QColor &color)
int UTILITE_EXP uStr2Int(const std::string &str)
int savePDALFile(const std::string &filePath, const pcl::PointCloud< pcl::PointXYZ > &cloud, const std::vector< int > &cameraIds=std::vector< int >(), bool binary=false)
Definition: PDALWriter.cpp:76
pcl::PolygonMesh::Ptr chiselToPolygonMesh(const chisel::MeshMap &meshMap, unsigned char r=100, unsigned char g=100, unsigned char b=100)
void incrementStep(int steps=1)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP subtractFiltering(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, float radiusSearch, int minNeighborsInRadius=1)
void getWeight(int signatureId, int &weight) const
Definition: DBDriver.cpp:849
pcl::TextureMesh::Ptr RTABMAP_EXP concatenateTextureMeshes(const std::list< pcl::TextureMesh::Ptr > &meshes)
std::shared_ptr< chisel::ColorImage< unsigned char > > colorImageToChisel(const cv::Mat &image)
std::map< int, Transform > RTABMAP_EXP radiusPosesFiltering(const std::map< int, Transform > &poses, float radius, float angle, bool keepLatest=true)
Definition: Graph.cpp:1253
cv::Mat RTABMAP_EXP cvtDepthToFloat(const cv::Mat &depth16U)
Definition: util2d.cpp:928
void setAutoClose(bool on, int delayedClosingTimeSec=-1)
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
CameraModel scaled(double scale) const
void setCancelButtonVisible(bool visible)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
pcl::IndicesPtr RTABMAP_EXP passThrough(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
void RTABMAP_EXP getMinMax3D(const cv::Mat &laserScan, cv::Point3f &min, cv::Point3f &max)
Definition: util3d.cpp:2481
f
const LaserScan & laserScanCompressed() const
Definition: SensorData.h:181
x
std::vector< pcl::Vertices > RTABMAP_EXP filterCloseVerticesFromMesh(const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr cloud, const std::vector< pcl::Vertices > &polygons, float radius, float angle, bool keepLatestInRadius)
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP laserScanToPointCloudRGBNormal(const LaserScan &laserScan, const Transform &transform=Transform(), unsigned char r=100, unsigned char g=100, unsigned char b=100)
Definition: util3d.cpp:2268
void apply(int id, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, bool rgb=true) const
static Transform getIdentity()
Definition: Transform.cpp:401
std::vector< int > RTABMAP_EXP filterNotUsedVerticesFromMesh(const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGBNormal > &outputCloud, std::vector< pcl::Vertices > &outputPolygons)
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:184
data
chisel::PinholeCamera cameraModelToChiselCamera(const CameraModel &camera)
std::set< K > uKeysSet(const std::map< K, V > &m)
Definition: UStl.h:186
std::list< V > uValuesList(const std::multimap< K, V > &mm)
Definition: UStl.h:117
float UTILITE_EXP uStr2Float(const std::string &str)
GLM_FUNC_DECL bool all(vecType< bool, P > const &v)
static const float vertices[]
Definition: quad.cpp:39
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
Definition: SensorData.cpp:227
const std::vector< StereoCameraModel > & stereoCameraModels() const
Definition: SensorData.h:237
void viewClouds(const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, const std::map< int, int > &mapIds, const QMap< int, Signature > &cachedSignatures, const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > &cachedClouds, const std::map< int, LaserScan > &cachedScans, const QString &workingDirectory, const ParametersMap &parameters)
bool getExportedClouds(const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, const std::map< int, int > &mapIds, const QMap< int, Signature > &cachedSignatures, const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > &cachedClouds, const std::map< int, LaserScan > &cachedScans, const QString &workingDirectory, const ParametersMap &parameters, std::map< int, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr > &clouds, std::map< int, pcl::PolygonMesh::Ptr > &meshes, std::map< int, pcl::TextureMesh::Ptr > &textureMeshes, std::vector< std::map< int, pcl::PointXY > > &textureVertexToPixels)
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
cv::Mat RTABMAP_EXP fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
Definition: util2d.cpp:1814
void setLighting(bool on)
Basic mathematics functions.
Some conversion functions.
int getWeight() const
Definition: Signature.h:74
void setPolygonPicking(bool enabled)
void buildPickingLocator(bool enable)
bool isEmpty() const
Definition: LaserScan.h:125
#define UFATAL(...)
pcl::IndicesPtr RTABMAP_EXP extractIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
bool addCloudTextureMesh(const std::string &id, const pcl::TextureMesh::Ptr &textureMesh, const cv::Mat &texture, const Transform &pose=Transform::getIdentity())
bool hasRGB() const
Definition: LaserScan.h:130
void setIntensityRedColormap(bool value)
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP mls(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float searchRadius=0.0f, int polygonialOrder=2, int upsamplingMethod=0, float upsamplingRadius=0.0f, float upsamplingStep=0.0f, int pointDensity=0, float dilationVoxelSize=1.0f, int dilationIterations=0)
#define UASSERT(condition)
Wrappers of STL for convenient functions.
std::string getPDALSupportedWriters()
Definition: PDALWriter.cpp:45
std::list< std::string > uSplit(const std::string &str, char separator=' ')
Definition: UStl.h:566
int id() const
Definition: SensorData.h:174
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:236
std::list< std::list< int > > RTABMAP_EXP clusterPolygons(const std::vector< std::set< int > > &neighborPolygons, int minClusterSize=0)
LaserScan RTABMAP_EXP commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, float groundNormalsUp=0.0f)
T uMax3(const T &a, const T &b, const T &c)
Definition: UMath.h:80
void saveClouds(const QString &workingDirectory, const std::map< int, Transform > &poses, const std::map< int, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr > &clouds, bool binaryMode=true, const std::vector< std::map< int, pcl::PointXY > > &pointToPixels=std::vector< std::map< int, pcl::PointXY > >())
void saveTextureMeshes(const QString &workingDirectory, const std::map< int, Transform > &poses, std::map< int, pcl::TextureMesh::Ptr > &textureMeshes, const QMap< int, Signature > &cachedSignatures, const std::vector< std::map< int, pcl::PointXY > > &textureVertexToPixels)
void RTABMAP_EXP appendMesh(pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudA, std::vector< pcl::Vertices > &polygonsA, const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudB, const std::vector< pcl::Vertices > &polygonsB)
bool getNodeInfo(int signatureId, Transform &pose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruthPose, std::vector< float > &velocity, GPS &gps, EnvSensors &sensors) const
Definition: DBDriver.cpp:776
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP randomSampling(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int samples)
cv::Mat depthRaw() const
Definition: SensorData.h:210
const cv::Mat & imageRaw() const
Definition: SensorData.h:183
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
Definition: util2d.cpp:1201
bool getCalibration(int signatureId, std::vector< CameraModel > &models, std::vector< StereoCameraModel > &stereoModels) const
Definition: DBDriver.cpp:726
std::vector< std::pair< std::pair< int, int >, pcl::PointXY > > RTABMAP_EXP projectCloudToCameras(const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::map< int, Transform > &cameraPoses, const std::map< int, std::vector< CameraModel > > &cameraModels, float maxDistance=0.0f, float maxAngle=0.0f, const std::vector< float > &roiRatios=std::vector< float >(), const cv::Mat &projMask=cv::Mat(), bool distanceToCamPolicy=false, const ProgressState *state=0)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
Definition: util3d.cpp:1056
chisel::PointCloudPtr pointCloudRGBToChisel(const typename pcl::PointCloud< PointRGBT > &cloud, const Transform &transform=Transform::getIdentity())
void setCloudPointSize(const std::string &id, int size)
void getNodeData(int signatureId, SensorData &data, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
Definition: DBDriver.cpp:675
bool empty() const
Definition: LaserScan.h:124
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
void setMaximumSteps(int steps)
pcl::PolygonMesh::Ptr RTABMAP_EXP createMesh(const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloudWithNormals, float gp3SearchRadius=0.025, float gp3Mu=2.5, int gp3MaximumNearestNeighbors=100, float gp3MaximumSurfaceAngle=M_PI/4, float gp3MinimumAngle=M_PI/18, float gp3MaximumAngle=2 *M_PI/3, bool gp3NormalConsistency=true)
std::vector< pcl::Vertices > RTABMAP_EXP organizedFastMesh(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, double angleTolerance, bool quad, int trianglePixelSize, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0))
ExportCloudsDialog(QWidget *parent=0)
bool getLaserScanInfo(int signatureId, LaserScan &info) const
Definition: DBDriver.cpp:752
bool uContains(const std::list< V > &list, const V &value)
Definition: UStl.h:409
void exportClouds(const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, const std::map< int, int > &mapIds, const QMap< int, Signature > &cachedSignatures, const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > &cachedClouds, const std::map< int, LaserScan > &cachedScans, const QString &workingDirectory, const ParametersMap &parameters)
bool isNull() const
Definition: Transform.cpp:107
cv::Mat RTABMAP_EXP mergeTextures(pcl::TextureMesh &mesh, const std::map< int, cv::Mat > &images, const std::map< int, CameraModel > &calibrations, const Memory *memory=0, const DBDriver *dbDriver=0, int textureSize=4096, int textureCount=1, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels=std::vector< std::map< int, pcl::PointXY > >(), bool gainCompensation=true, float gainBeta=10.0f, bool gainRGB=true, bool blending=true, int blendingDecimation=0, int brightnessContrastRatioLow=0, int brightnessContrastRatioHigh=0, bool exposureFusion=false, const ProgressState *state=0, unsigned char blankValue=255, std::map< int, std::map< int, cv::Vec4d > > *gains=0, std::map< int, std::map< int, cv::Mat > > *blendingGains=0, std::pair< float, float > *contrastValues=0)
bool addCloud(const std::string &id, const pcl::PCLPointCloud2Ptr &binaryCloud, const Transform &pose, bool rgb, bool hasNormals, bool hasIntensity, const QColor &color=QColor(), int viewport=1)
#define false
Definition: ConvertUTF.c:56
void uSleep(unsigned int ms)
pcl::IndicesPtr RTABMAP_EXP radiusFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(const pcl::PolygonMesh::Ptr &mesh, const std::map< int, Transform > &poses, const std::map< int, CameraModel > &cameraModels, const std::map< int, cv::Mat > &cameraDepths, float maxDistance=0.0f, float maxDepthError=0.0f, float maxAngle=0.0f, int minClusterSize=50, const std::vector< float > &roiRatios=std::vector< float >(), const ProgressState *state=0, std::vector< std::map< int, pcl::PointXY > > *vertexToPixels=0, bool distanceToCamPolicy=false)
std::vector< pcl::Vertices > RTABMAP_EXP filterInvalidPolygons(const std::vector< pcl::Vertices > &polygons)
const LaserScan & laserScanRaw() const
Definition: SensorData.h:185
#define UDEBUG(...)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
SensorData & sensorData()
Definition: Signature.h:137
bool isCanceled() const
Definition: ProgressState.h:51
void RTABMAP_EXP cleanTextureMesh(pcl::TextureMesh &textureMesh, int minClusterSize)
Ui_ExportCloudsDialog * _ui
void RTABMAP_EXP createPolygonIndexes(const std::vector< pcl::Vertices > &polygons, int cloudSize, std::vector< std::set< int > > &neighborPolygons, std::vector< std::set< int > > &vertexPolygons)
Given a set of polygons, create two indexes: polygons to neighbor polygons and vertices to polygons...
#define UERROR(...)
int getIndex(int id) const
pcl::IndicesPtr RTABMAP_EXP cropBox(const pcl::PCLPointCloud2::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
cv::Mat RTABMAP_EXP fillDepthHoles(const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
Definition: util2d.cpp:1439
ULogger class and convenient macros.
#define UWARN(...)
void setBackfaceCulling(bool enabled, bool frontfaceCulling)
void feed(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloudA, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloudB, const Transform &transformB)
void saveMeshes(const QString &workingDirectory, const std::map< int, Transform > &poses, const std::map< int, pcl::PolygonMesh::Ptr > &meshes, bool binaryMode=true)
model
Definition: trace.py:4
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
void RTABMAP_EXP adjustNormalsToViewPoints(const std::map< int, Transform > &poses, const pcl::PointCloud< pcl::PointXYZ >::Ptr &rawCloud, const std::vector< int > &rawCameraIndices, pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, float groundNormalsUp=0.0f)
std::map< EnvSensor::Type, EnvSensor > EnvSensors
Definition: EnvSensor.h:81
bool addCloudMesh(const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const std::vector< pcl::Vertices > &polygons, const Transform &pose=Transform::getIdentity())
float RTABMAP_EXP getDepth(const cv::Mat &depthImage, float x, float y, bool smoothing, float depthErrorRatio=0.02f, bool estWithNeighborsIfNull=false)
Definition: util2d.cpp:947
void appendText(const QString &text, const QColor &color=Qt::black)
static bool removeDirRecursively(const QString &dirName)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
std::string UTILITE_EXP uFormat(const char *fmt,...)
std::string UTILITE_EXP uNumber2Str(unsigned int number)
Definition: UConversion.cpp:91
std::map< int, Transform > filterNodes(const std::map< int, Transform > &poses)
void uncompressDataConst(cv::Mat *imageRaw, cv::Mat *depthOrRightRaw, LaserScan *laserScanRaw=0, cv::Mat *userDataRaw=0, cv::Mat *groundCellsRaw=0, cv::Mat *obstacleCellsRaw=0, cv::Mat *emptyCellsRaw=0) const
Definition: SensorData.cpp:623
const cv::Mat & imageCompressed() const
Definition: SensorData.h:179
Transform localTransform() const
Definition: LaserScan.h:122
std::shared_ptr< chisel::DepthImage< float > > depthImageToChisel(const cv::Mat &image)
double getGain(int id, double *r=0, double *g=0, double *b=0) const
bool RTABMAP_EXP multiBandTexturing(const std::string &outputOBJPath, const pcl::PCLPointCloud2 &cloud, const std::vector< pcl::Vertices > &polygons, const std::map< int, Transform > &cameraPoses, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels, const std::map< int, cv::Mat > &images, const std::map< int, std::vector< CameraModel > > &cameraModels, const Memory *memory=0, const DBDriver *dbDriver=0, unsigned int textureSize=8192, unsigned int textureDownscale=2, const std::string &nbContrib="1 5 10 0", const std::string &textureFormat="jpg", const std::map< int, std::map< int, cv::Vec4d > > &gains=std::map< int, std::map< int, cv::Vec4d > >(), const std::map< int, std::map< int, cv::Mat > > &blendingGains=std::map< int, std::map< int, cv::Mat > >(), const std::pair< float, float > &contrastValues=std::pair< float, float >(0, 0), bool gainRGB=true, unsigned int unwrapMethod=0, bool fillHoles=false, unsigned int padding=5, double bestScoreThreshold=0.1, double angleHardThreshold=90.0, bool forceVisibleByAllVertices=false)
Transform inverse() const
Definition: Transform.cpp:178
std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr, pcl::IndicesPtr > > getClouds(const std::map< int, Transform > &poses, const QMap< int, Signature > &cachedSignatures, const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > &cachedClouds, const std::map< int, LaserScan > &cachedScans, const ParametersMap &parameters, bool &has2dScans, bool &scansHaveRGB) const
void setIntensityRainbowColormap(bool value)
LaserScan RTABMAP_EXP adjustNormalsToViewPoint(const LaserScan &scan, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0), float groundNormalsUp=0.0f)
#define UINFO(...)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28