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 namespace rtabmap {
80 
82  QDialog(parent),
83  _canceled(false),
84  _compensator(0),
85  _dbDriver(0)
86 {
87  _ui = new Ui_ExportCloudsDialog();
88  _ui->setupUi(this);
89 
90  connect(_ui->buttonBox->button(QDialogButtonBox::RestoreDefaults), SIGNAL(clicked()), this, SLOT(restoreDefaults()));
91  QPushButton * loadSettingsButton = _ui->buttonBox->addButton("Load Settings", QDialogButtonBox::ActionRole);
92  QPushButton * saveSettingsButton = _ui->buttonBox->addButton("Save Settings", QDialogButtonBox::ActionRole);
93  connect(loadSettingsButton, SIGNAL(clicked()), this, SLOT(loadSettings()));
94  connect(saveSettingsButton, SIGNAL(clicked()), this, SLOT(saveSettings()));
95 
97  _ui->comboBox_upsamplingMethod->setItemData(1, 0, Qt::UserRole - 1); // disable DISTINCT_CLOUD
98 
99  connect(_ui->checkBox_fromDepth, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
100  connect(_ui->checkBox_fromDepth, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
101  connect(_ui->checkBox_binary, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
102  connect(_ui->spinBox_normalKSearch, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
103  connect(_ui->doubleSpinBox_normalRadiusSearch, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
104  connect(_ui->comboBox_pipeline, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
105  connect(_ui->comboBox_pipeline, SIGNAL(currentIndexChanged(int)), this, SLOT(updateReconstructionFlavor()));
106  connect(_ui->comboBox_meshingApproach, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
107  connect(_ui->comboBox_meshingApproach, SIGNAL(currentIndexChanged(int)), this, SLOT(updateReconstructionFlavor()));
108 
109  connect(_ui->checkBox_regenerate, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
110  connect(_ui->checkBox_regenerate, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
111  connect(_ui->spinBox_decimation, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
112  connect(_ui->doubleSpinBox_maxDepth, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
113  connect(_ui->doubleSpinBox_minDepth, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
114  connect(_ui->spinBox_fillDepthHoles, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
115  connect(_ui->spinBox_fillDepthHolesError, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
116  connect(_ui->lineEdit_roiRatios, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
117  connect(_ui->lineEdit_distortionModel, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
118  connect(_ui->toolButton_distortionModel, SIGNAL(clicked()), this, SLOT(selectDistortionModel()));
119 
120  connect(_ui->checkBox_bilateral, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
121  connect(_ui->checkBox_bilateral, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
122  connect(_ui->doubleSpinBox_bilateral_sigmaS, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
123  connect(_ui->doubleSpinBox_bilateral_sigmaR, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
124 
125  connect(_ui->checkBox_filtering, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
126  connect(_ui->checkBox_filtering, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
127  connect(_ui->doubleSpinBox_filteringRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
128  connect(_ui->spinBox_filteringMinNeighbors, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
129 
130  connect(_ui->checkBox_assemble, SIGNAL(clicked(bool)), this, SIGNAL(configChanged()));
131  connect(_ui->checkBox_assemble, SIGNAL(clicked(bool)), this, SLOT(updateReconstructionFlavor()));
132  connect(_ui->doubleSpinBox_voxelSize_assembled, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
133  connect(_ui->comboBox_frame, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
134  connect(_ui->comboBox_frame, SIGNAL(currentIndexChanged(int)), this, SLOT(updateReconstructionFlavor()));
135 
136  connect(_ui->checkBox_subtraction, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
137  connect(_ui->checkBox_subtraction, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
138  connect(_ui->doubleSpinBox_subtractPointFilteringRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
139  connect(_ui->doubleSpinBox_subtractPointFilteringAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
140  connect(_ui->spinBox_subtractFilteringMinPts, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
141 
142  connect(_ui->checkBox_smoothing, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
143  connect(_ui->checkBox_smoothing, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
144  connect(_ui->doubleSpinBox_mlsRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
145  connect(_ui->spinBox_polygonialOrder, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
146  connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
147  connect(_ui->doubleSpinBox_sampleStep, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
148  connect(_ui->spinBox_randomPoints, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
149  connect(_ui->doubleSpinBox_dilationVoxelSize, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
150  connect(_ui->spinBox_dilationSteps, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
151  connect(_ui->doubleSpinBox_mls_outputVoxelSize, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
152  _ui->stackedWidget_upsampling->setCurrentIndex(_ui->comboBox_upsamplingMethod->currentIndex());
153  connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), _ui->stackedWidget_upsampling, SLOT(setCurrentIndex(int)));
154  connect(_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(int)), this, SLOT(updateMLSGrpVisibility()));
155 
156  connect(_ui->checkBox_gainCompensation, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
157  connect(_ui->checkBox_gainCompensation, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
158  connect(_ui->doubleSpinBox_gainRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
159  connect(_ui->doubleSpinBox_gainOverlap, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
160  connect(_ui->doubleSpinBox_gainBeta, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
161  connect(_ui->checkBox_gainRGB, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
162  connect(_ui->checkBox_gainFull, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
163  connect(_ui->spinBox_textureBrightnessContrastRatioLow, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
164  connect(_ui->spinBox_textureBrightnessContrastRatioHigh, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
165  connect(_ui->checkBox_exposureFusion, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
166  connect(_ui->checkBox_blending, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
167  connect(_ui->comboBox_blendingDecimation, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
168 
169  connect(_ui->checkBox_meshing, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
170  connect(_ui->checkBox_meshing, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
171  connect(_ui->checkBox_meshing, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
172  connect(_ui->doubleSpinBox_gp3Radius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
173  connect(_ui->doubleSpinBox_gp3Mu, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
174  connect(_ui->doubleSpinBox_meshDecimationFactor, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
175  connect(_ui->doubleSpinBox_meshDecimationFactor, SIGNAL(valueChanged(double)), this, SLOT(updateReconstructionFlavor()));
176  connect(_ui->spinBox_meshMaxPolygons, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
177  connect(_ui->spinBox_meshMaxPolygons, SIGNAL(valueChanged(int)), this, SLOT(updateReconstructionFlavor()));
178  connect(_ui->doubleSpinBox_transferColorRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
179  connect(_ui->checkBox_cleanMesh, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
180  connect(_ui->spinBox_mesh_minClusterSize, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
181  connect(_ui->checkBox_textureMapping, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
182  connect(_ui->checkBox_textureMapping, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
183  connect(_ui->comboBox_meshingTextureFormat, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
184  connect(_ui->comboBox_meshingTextureSize, SIGNAL(currentIndexChanged(int)), this, SIGNAL(configChanged()));
185  connect(_ui->spinBox_mesh_maxTextures, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
186  connect(_ui->doubleSpinBox_meshingTextureMaxDistance, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
187  connect(_ui->doubleSpinBox_meshingTextureMaxDepthError, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
188  connect(_ui->doubleSpinBox_meshingTextureMaxAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
189  connect(_ui->spinBox_mesh_minTextureClusterSize, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
190  connect(_ui->lineEdit_meshingTextureRoiRatios, SIGNAL(textChanged(const QString &)), this, SIGNAL(configChanged()));
191  connect(_ui->checkBox_cameraFilter, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
192  connect(_ui->checkBox_cameraFilter, SIGNAL(stateChanged(int)), this, SLOT(updateReconstructionFlavor()));
193  connect(_ui->doubleSpinBox_cameraFilterRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
194  connect(_ui->doubleSpinBox_cameraFilterAngle, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
195  connect(_ui->doubleSpinBox_cameraFilterVel, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
196  connect(_ui->doubleSpinBox_cameraFilterVelRad, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
197  connect(_ui->doubleSpinBox_laplacianVariance, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
198 
199  connect(_ui->checkBox_poisson_outputPolygons, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
200  connect(_ui->checkBox_poisson_manifold, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
201  connect(_ui->spinBox_poisson_depth, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
202  connect(_ui->spinBox_poisson_iso, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
203  connect(_ui->spinBox_poisson_solver, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
204  connect(_ui->spinBox_poisson_minDepth, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
205  connect(_ui->doubleSpinBox_poisson_samples, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
206  connect(_ui->doubleSpinBox_poisson_pointWeight, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
207  connect(_ui->doubleSpinBox_poisson_scale, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
208 
209  connect(_ui->doubleSpinBox_cputsdf_size, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
210  connect(_ui->doubleSpinBox_cputsdf_resolution, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
211  connect(_ui->doubleSpinBox_cputsdf_tuncPos, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
212  connect(_ui->doubleSpinBox_cputsdf_tuncNeg, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
213  connect(_ui->doubleSpinBox_cputsdf_minWeight, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
214  connect(_ui->doubleSpinBox_cputsdf_flattenRadius, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
215  connect(_ui->spinBox_cputsdf_randomSplit, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
216 
217  connect(_ui->checkBox_openchisel_mergeVertices, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
218  connect(_ui->spinBox_openchisel_chunk_size_x, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
219  connect(_ui->spinBox_openchisel_chunk_size_y, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
220  connect(_ui->spinBox_openchisel_chunk_size_z, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
221  connect(_ui->doubleSpinBox_openchisel_truncation_constant, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
222  connect(_ui->doubleSpinBox_openchisel_truncation_linear, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
223  connect(_ui->doubleSpinBox_openchisel_truncation_quadratic, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
224  connect(_ui->doubleSpinBox_openchisel_truncation_scale, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
225  connect(_ui->spinBox_openchisel_integration_weight, SIGNAL(valueChanged(int)), this, SIGNAL(configChanged()));
226  connect(_ui->checkBox_openchisel_use_voxel_carving, SIGNAL(stateChanged(int)), this, SIGNAL(configChanged()));
227  connect(_ui->doubleSpinBox_openchisel_carving_dist_m, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
228  connect(_ui->doubleSpinBox_openchisel_near_plane_dist, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
229  connect(_ui->doubleSpinBox_openchisel_far_plane_dist, SIGNAL(valueChanged(double)), this, SIGNAL(configChanged()));
230 
231 
232  _progressDialog = new ProgressDialog(this);
233  _progressDialog->setVisible(false);
234  _progressDialog->setAutoClose(true, 2);
235  _progressDialog->setMinimumWidth(600);
237  connect(_progressDialog, SIGNAL(canceled()), this, SLOT(cancel()));
238 
239 #ifdef DISABLE_VTK
240  _ui->doubleSpinBox_meshDecimationFactor->setEnabled(false);
241  _ui->spinBox_meshMaxPolygons->setEnabled(false);
242  _ui->label_meshDecimation->setEnabled(false);
243  _ui->label_meshMaxPolygons->setEnabled(false);
244 #endif
245 
246 #if CV_MAJOR_VERSION < 3
247  _ui->checkBox_exposureFusion->setEnabled(false);
248  _ui->checkBox_exposureFusion->setChecked(false);
249  _ui->label_exposureFusion->setEnabled(false);
250 #endif
251 }
252 
254 {
255  delete _ui;
256  delete _compensator;
257 }
258 
260 {
261  _ui->groupBox->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 0);
262  _ui->groupBox_2->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 1);
263  _ui->groupBox_3->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 2);
264  _ui->groupBox_4->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 3);
265  _ui->groupBox_5->setVisible(_ui->comboBox_upsamplingMethod->currentIndex() == 4);
266 }
267 
269 {
270  _canceled = true;
271  _progressDialog->appendText(tr("Canceled!"));
272 }
273 
275 {
276  if(enabled)
277  {
278  _ui->checkBox_assemble->setChecked(true);
279  _ui->checkBox_assemble->setEnabled(false);
280  }
281  else
282  {
283  _ui->checkBox_assemble->setEnabled(true);
284  }
285 }
286 
288 {
290 }
291 
292 void ExportCloudsDialog::saveSettings(QSettings & settings, const QString & group) const
293 {
294  if(!group.isEmpty())
295  {
296  settings.beginGroup(group);
297  }
298  settings.setValue("pipeline", _ui->comboBox_pipeline->currentIndex());
299  settings.setValue("from_depth", _ui->checkBox_fromDepth->isChecked());
300  settings.setValue("binary", _ui->checkBox_binary->isChecked());
301  settings.setValue("normals_k", _ui->spinBox_normalKSearch->value());
302  settings.setValue("normals_radius", _ui->doubleSpinBox_normalRadiusSearch->value());
303 
304  settings.setValue("regenerate", _ui->checkBox_regenerate->isChecked());
305  settings.setValue("regenerate_decimation", _ui->spinBox_decimation->value());
306  settings.setValue("regenerate_max_depth", _ui->doubleSpinBox_maxDepth->value());
307  settings.setValue("regenerate_min_depth", _ui->doubleSpinBox_minDepth->value());
308  settings.setValue("regenerate_fill_size", _ui->spinBox_fillDepthHoles->value());
309  settings.setValue("regenerate_fill_error", _ui->spinBox_fillDepthHolesError->value());
310  settings.setValue("regenerate_roi", _ui->lineEdit_roiRatios->text());
311  settings.setValue("regenerate_distortion_model", _ui->lineEdit_distortionModel->text());
312 
313  settings.setValue("bilateral", _ui->checkBox_bilateral->isChecked());
314  settings.setValue("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value());
315  settings.setValue("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value());
316 
317  settings.setValue("filtering", _ui->checkBox_filtering->isChecked());
318  settings.setValue("filtering_radius", _ui->doubleSpinBox_filteringRadius->value());
319  settings.setValue("filtering_min_neighbors", _ui->spinBox_filteringMinNeighbors->value());
320 
321  settings.setValue("assemble", _ui->checkBox_assemble->isChecked());
322  settings.setValue("assemble_voxel",_ui->doubleSpinBox_voxelSize_assembled->value());
323  settings.setValue("frame",_ui->comboBox_frame->currentIndex());
324 
325  settings.setValue("subtract",_ui->checkBox_subtraction->isChecked());
326  settings.setValue("subtract_point_radius",_ui->doubleSpinBox_subtractPointFilteringRadius->value());
327  settings.setValue("subtract_point_angle",_ui->doubleSpinBox_subtractPointFilteringAngle->value());
328  settings.setValue("subtract_min_neighbors",_ui->spinBox_subtractFilteringMinPts->value());
329 
330  settings.setValue("mls", _ui->checkBox_smoothing->isChecked());
331  settings.setValue("mls_radius", _ui->doubleSpinBox_mlsRadius->value());
332  settings.setValue("mls_polygonial_order", _ui->spinBox_polygonialOrder->value());
333  settings.setValue("mls_upsampling_method", _ui->comboBox_upsamplingMethod->currentIndex());
334  settings.setValue("mls_upsampling_radius", _ui->doubleSpinBox_sampleRadius->value());
335  settings.setValue("mls_upsampling_step", _ui->doubleSpinBox_sampleStep->value());
336  settings.setValue("mls_point_density", _ui->spinBox_randomPoints->value());
337  settings.setValue("mls_dilation_voxel_size", _ui->doubleSpinBox_dilationVoxelSize->value());
338  settings.setValue("mls_dilation_iterations", _ui->spinBox_dilationSteps->value());
339  settings.setValue("mls_output_voxel_size", _ui->doubleSpinBox_mls_outputVoxelSize->value());
340 
341  settings.setValue("gain", _ui->checkBox_gainCompensation->isChecked());
342  settings.setValue("gain_radius", _ui->doubleSpinBox_gainRadius->value());
343  settings.setValue("gain_overlap", _ui->doubleSpinBox_gainOverlap->value());
344  settings.setValue("gain_beta", _ui->doubleSpinBox_gainBeta->value());
345  settings.setValue("gain_rgb", _ui->checkBox_gainRGB->isChecked());
346  settings.setValue("gain_full", _ui->checkBox_gainFull->isChecked());
347 
348  settings.setValue("mesh", _ui->checkBox_meshing->isChecked());
349  settings.setValue("mesh_radius", _ui->doubleSpinBox_gp3Radius->value());
350  settings.setValue("mesh_mu", _ui->doubleSpinBox_gp3Mu->value());
351  settings.setValue("mesh_decimation_factor", _ui->doubleSpinBox_meshDecimationFactor->value());
352  settings.setValue("mesh_max_polygons", _ui->spinBox_meshMaxPolygons->value());
353  settings.setValue("mesh_color_radius", _ui->doubleSpinBox_transferColorRadius->value());
354  settings.setValue("mesh_clean", _ui->checkBox_cleanMesh->isChecked());
355  settings.setValue("mesh_min_cluster_size", _ui->spinBox_mesh_minClusterSize->value());
356 
357  settings.setValue("mesh_dense_strategy", _ui->comboBox_meshingApproach->currentIndex());
358 
359  settings.setValue("mesh_texture", _ui->checkBox_textureMapping->isChecked());
360  settings.setValue("mesh_textureFormat", _ui->comboBox_meshingTextureFormat->currentIndex());
361  settings.setValue("mesh_textureSize", _ui->comboBox_meshingTextureSize->currentIndex());
362  settings.setValue("mesh_textureMaxCount", _ui->spinBox_mesh_maxTextures->value());
363  settings.setValue("mesh_textureMaxDistance", _ui->doubleSpinBox_meshingTextureMaxDistance->value());
364  settings.setValue("mesh_textureMaxDepthError", _ui->doubleSpinBox_meshingTextureMaxDepthError->value());
365  settings.setValue("mesh_textureMaxAngle", _ui->doubleSpinBox_meshingTextureMaxAngle->value());
366  settings.setValue("mesh_textureMinCluster", _ui->spinBox_mesh_minTextureClusterSize->value());
367  settings.setValue("mesh_textureRoiRatios", _ui->lineEdit_meshingTextureRoiRatios->text());
368  settings.setValue("mesh_textureCameraFiltering", _ui->checkBox_cameraFilter->isChecked());
369  settings.setValue("mesh_textureCameraFilteringRadius", _ui->doubleSpinBox_cameraFilterRadius->value());
370  settings.setValue("mesh_textureCameraFilteringAngle", _ui->doubleSpinBox_cameraFilterAngle->value());
371  settings.setValue("mesh_textureCameraFilteringVel", _ui->doubleSpinBox_cameraFilterVel->value());
372  settings.setValue("mesh_textureCameraFilteringVelRad", _ui->doubleSpinBox_cameraFilterVelRad->value());
373  settings.setValue("mesh_textureCameraFilteringLaplacian", _ui->doubleSpinBox_laplacianVariance->value());
374  settings.setValue("mesh_textureBrightnessConstrastRatioLow", _ui->spinBox_textureBrightnessContrastRatioLow->value());
375  settings.setValue("mesh_textureBrightnessConstrastRatioHigh", _ui->spinBox_textureBrightnessContrastRatioHigh->value());
376  settings.setValue("mesh_textureExposureFusion", _ui->checkBox_exposureFusion->isChecked());
377  settings.setValue("mesh_textureBlending", _ui->checkBox_blending->isChecked());
378  settings.setValue("mesh_textureBlendingDecimation", _ui->comboBox_blendingDecimation->currentIndex());
379 
380 
381  settings.setValue("mesh_angle_tolerance", _ui->doubleSpinBox_mesh_angleTolerance->value());
382  settings.setValue("mesh_quad", _ui->checkBox_mesh_quad->isChecked());
383  settings.setValue("mesh_triangle_size", _ui->spinBox_mesh_triangleSize->value());
384 
385  settings.setValue("poisson_outputPolygons", _ui->checkBox_poisson_outputPolygons->isChecked());
386  settings.setValue("poisson_manifold", _ui->checkBox_poisson_manifold->isChecked());
387  settings.setValue("poisson_depth", _ui->spinBox_poisson_depth->value());
388  settings.setValue("poisson_iso", _ui->spinBox_poisson_iso->value());
389  settings.setValue("poisson_solver", _ui->spinBox_poisson_solver->value());
390  settings.setValue("poisson_minDepth", _ui->spinBox_poisson_minDepth->value());
391  settings.setValue("poisson_samples", _ui->doubleSpinBox_poisson_samples->value());
392  settings.setValue("poisson_pointWeight", _ui->doubleSpinBox_poisson_pointWeight->value());
393  settings.setValue("poisson_scale", _ui->doubleSpinBox_poisson_scale->value());
394 
395  settings.setValue("cputsdf_size", _ui->doubleSpinBox_cputsdf_size->value());
396  settings.setValue("cputsdf_resolution", _ui->doubleSpinBox_cputsdf_resolution->value());
397  settings.setValue("cputsdf_truncPos", _ui->doubleSpinBox_cputsdf_tuncPos->value());
398  settings.setValue("cputsdf_truncNeg", _ui->doubleSpinBox_cputsdf_tuncNeg->value());
399  settings.setValue("cputsdf_minWeight", _ui->doubleSpinBox_cputsdf_minWeight->value());
400  settings.setValue("cputsdf_flattenRadius", _ui->doubleSpinBox_cputsdf_flattenRadius->value());
401  settings.setValue("cputsdf_randomSplit", _ui->spinBox_cputsdf_randomSplit->value());
402 
403  settings.setValue("openchisel_merge_vertices", _ui->checkBox_openchisel_mergeVertices->isChecked());
404  settings.setValue("openchisel_chunk_size_x", _ui->spinBox_openchisel_chunk_size_x->value());
405  settings.setValue("openchisel_chunk_size_y", _ui->spinBox_openchisel_chunk_size_y->value());
406  settings.setValue("openchisel_chunk_size_z", _ui->spinBox_openchisel_chunk_size_z->value());
407  settings.setValue("openchisel_truncation_constant", _ui->doubleSpinBox_openchisel_truncation_constant->value());
408  settings.setValue("openchisel_truncation_linear", _ui->doubleSpinBox_openchisel_truncation_linear->value());
409  settings.setValue("openchisel_truncation_quadratic", _ui->doubleSpinBox_openchisel_truncation_quadratic->value());
410  settings.setValue("openchisel_truncation_scale", _ui->doubleSpinBox_openchisel_truncation_scale->value());
411  settings.setValue("openchisel_integration_weight", _ui->spinBox_openchisel_integration_weight->value());
412  settings.setValue("openchisel_use_voxel_carving", _ui->checkBox_openchisel_use_voxel_carving->isChecked());
413  settings.setValue("openchisel_carving_dist_m", _ui->doubleSpinBox_openchisel_carving_dist_m->value());
414  settings.setValue("openchisel_near_plane_dist", _ui->doubleSpinBox_openchisel_near_plane_dist->value());
415  settings.setValue("openchisel_far_plane_dist", _ui->doubleSpinBox_openchisel_far_plane_dist->value());
416 
417  if(!group.isEmpty())
418  {
419  settings.endGroup();
420  }
421 }
422 
423 void ExportCloudsDialog::loadSettings(QSettings & settings, const QString & group)
424 {
425  if(!group.isEmpty())
426  {
427  settings.beginGroup(group);
428  }
429 
430  _ui->comboBox_pipeline->setCurrentIndex(settings.value("pipeline", _ui->comboBox_pipeline->currentIndex()).toInt());
431  _ui->checkBox_fromDepth->setChecked(settings.value("from_depth", _ui->checkBox_fromDepth->isChecked()).toBool());
432  _ui->checkBox_binary->setChecked(settings.value("binary", _ui->checkBox_binary->isChecked()).toBool());
433  _ui->spinBox_normalKSearch->setValue(settings.value("normals_k", _ui->spinBox_normalKSearch->value()).toInt());
434  _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value("normals_radius", _ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
435 
436  _ui->checkBox_regenerate->setChecked(settings.value("regenerate", _ui->checkBox_regenerate->isChecked()).toBool());
437  _ui->spinBox_decimation->setValue(settings.value("regenerate_decimation", _ui->spinBox_decimation->value()).toInt());
438  _ui->doubleSpinBox_maxDepth->setValue(settings.value("regenerate_max_depth", _ui->doubleSpinBox_maxDepth->value()).toDouble());
439  _ui->doubleSpinBox_minDepth->setValue(settings.value("regenerate_min_depth", _ui->doubleSpinBox_minDepth->value()).toDouble());
440  _ui->spinBox_fillDepthHoles->setValue(settings.value("regenerate_fill_size", _ui->spinBox_fillDepthHoles->value()).toInt());
441  _ui->spinBox_fillDepthHolesError->setValue(settings.value("regenerate_fill_error", _ui->spinBox_fillDepthHolesError->value()).toInt());
442  _ui->lineEdit_roiRatios->setText(settings.value("regenerate_roi", _ui->lineEdit_roiRatios->text()).toString());
443  _ui->lineEdit_distortionModel->setText(settings.value("regenerate_distortion_model", _ui->lineEdit_distortionModel->text()).toString());
444 
445  _ui->checkBox_bilateral->setChecked(settings.value("bilateral", _ui->checkBox_bilateral->isChecked()).toBool());
446  _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value("bilateral_sigma_s", _ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
447  _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value("bilateral_sigma_r", _ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
448 
449  _ui->checkBox_filtering->setChecked(settings.value("filtering", _ui->checkBox_filtering->isChecked()).toBool());
450  _ui->doubleSpinBox_filteringRadius->setValue(settings.value("filtering_radius", _ui->doubleSpinBox_filteringRadius->value()).toDouble());
451  _ui->spinBox_filteringMinNeighbors->setValue(settings.value("filtering_min_neighbors", _ui->spinBox_filteringMinNeighbors->value()).toInt());
452 
453  if(_ui->checkBox_assemble->isEnabled())
454  {
455  _ui->checkBox_assemble->setChecked(settings.value("assemble", _ui->checkBox_assemble->isChecked()).toBool());
456  }
457  _ui->doubleSpinBox_voxelSize_assembled->setValue(settings.value("assemble_voxel", _ui->doubleSpinBox_voxelSize_assembled->value()).toDouble());
458  _ui->comboBox_frame->setCurrentIndex(settings.value("frame", _ui->comboBox_frame->currentIndex()).toInt());
459 
460  _ui->checkBox_subtraction->setChecked(settings.value("subtract",_ui->checkBox_subtraction->isChecked()).toBool());
461  _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(settings.value("subtract_point_radius",_ui->doubleSpinBox_subtractPointFilteringRadius->value()).toDouble());
462  _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(settings.value("subtract_point_angle",_ui->doubleSpinBox_subtractPointFilteringAngle->value()).toDouble());
463  _ui->spinBox_subtractFilteringMinPts->setValue(settings.value("subtract_min_neighbors",_ui->spinBox_subtractFilteringMinPts->value()).toInt());
464 
465  _ui->checkBox_smoothing->setChecked(settings.value("mls", _ui->checkBox_smoothing->isChecked()).toBool());
466  _ui->doubleSpinBox_mlsRadius->setValue(settings.value("mls_radius", _ui->doubleSpinBox_mlsRadius->value()).toDouble());
467  _ui->spinBox_polygonialOrder->setValue(settings.value("mls_polygonial_order", _ui->spinBox_polygonialOrder->value()).toInt());
468  _ui->comboBox_upsamplingMethod->setCurrentIndex(settings.value("mls_upsampling_method", _ui->comboBox_upsamplingMethod->currentIndex()).toInt());
469  _ui->doubleSpinBox_sampleRadius->setValue(settings.value("mls_upsampling_radius", _ui->doubleSpinBox_sampleRadius->value()).toDouble());
470  _ui->doubleSpinBox_sampleStep->setValue(settings.value("mls_upsampling_step", _ui->doubleSpinBox_sampleStep->value()).toDouble());
471  _ui->spinBox_randomPoints->setValue(settings.value("mls_point_density", _ui->spinBox_randomPoints->value()).toInt());
472  _ui->doubleSpinBox_dilationVoxelSize->setValue(settings.value("mls_dilation_voxel_size", _ui->doubleSpinBox_dilationVoxelSize->value()).toDouble());
473  _ui->spinBox_dilationSteps->setValue(settings.value("mls_dilation_iterations", _ui->spinBox_dilationSteps->value()).toInt());
474  _ui->doubleSpinBox_mls_outputVoxelSize->setValue(settings.value("mls_output_voxel_size", _ui->doubleSpinBox_mls_outputVoxelSize->value()).toInt());
475 
476  _ui->checkBox_gainCompensation->setChecked(settings.value("gain", _ui->checkBox_gainCompensation->isChecked()).toBool());
477  _ui->doubleSpinBox_gainRadius->setValue(settings.value("gain_radius", _ui->doubleSpinBox_gainRadius->value()).toDouble());
478  _ui->doubleSpinBox_gainOverlap->setValue(settings.value("gain_overlap", _ui->doubleSpinBox_gainOverlap->value()).toDouble());
479  _ui->doubleSpinBox_gainBeta->setValue(settings.value("gain_beta", _ui->doubleSpinBox_gainBeta->value()).toDouble());
480  _ui->checkBox_gainRGB->setChecked(settings.value("gain_rgb", _ui->checkBox_gainRGB->isChecked()).toBool());
481  _ui->checkBox_gainFull->setChecked(settings.value("gain_full", _ui->checkBox_gainFull->isChecked()).toBool());
482 
483  _ui->checkBox_meshing->setChecked(settings.value("mesh", _ui->checkBox_meshing->isChecked()).toBool());
484  _ui->doubleSpinBox_gp3Radius->setValue(settings.value("mesh_radius", _ui->doubleSpinBox_gp3Radius->value()).toDouble());
485  _ui->doubleSpinBox_gp3Mu->setValue(settings.value("mesh_mu", _ui->doubleSpinBox_gp3Mu->value()).toDouble());
486  _ui->doubleSpinBox_meshDecimationFactor->setValue(settings.value("mesh_decimation_factor",_ui->doubleSpinBox_meshDecimationFactor->value()).toDouble());
487  _ui->spinBox_meshMaxPolygons->setValue(settings.value("mesh_max_polygons",_ui->spinBox_meshMaxPolygons->value()).toDouble());
488  _ui->doubleSpinBox_transferColorRadius->setValue(settings.value("mesh_color_radius",_ui->doubleSpinBox_transferColorRadius->value()).toDouble());
489  _ui->checkBox_cleanMesh->setChecked(settings.value("mesh_clean",_ui->checkBox_cleanMesh->isChecked()).toBool());
490  _ui->spinBox_mesh_minClusterSize->setValue(settings.value("mesh_min_cluster_size", _ui->spinBox_mesh_minClusterSize->value()).toInt());
491 
492  _ui->comboBox_meshingApproach->setCurrentIndex(settings.value("mesh_dense_strategy", _ui->comboBox_meshingApproach->currentIndex()).toInt());
493 
494  _ui->checkBox_textureMapping->setChecked(settings.value("mesh_texture", _ui->checkBox_textureMapping->isChecked()).toBool());
495  _ui->comboBox_meshingTextureFormat->setCurrentIndex(settings.value("mesh_textureFormat", _ui->comboBox_meshingTextureFormat->currentIndex()).toInt());
496  _ui->comboBox_meshingTextureSize->setCurrentIndex(settings.value("mesh_textureSize", _ui->comboBox_meshingTextureSize->currentIndex()).toInt());
497  _ui->spinBox_mesh_maxTextures->setValue(settings.value("mesh_textureMaxCount", _ui->spinBox_mesh_maxTextures->value()).toInt());
498  _ui->doubleSpinBox_meshingTextureMaxDistance->setValue(settings.value("mesh_textureMaxDistance", _ui->doubleSpinBox_meshingTextureMaxDistance->value()).toDouble());
499  _ui->doubleSpinBox_meshingTextureMaxDepthError->setValue(settings.value("mesh_textureMaxDepthError", _ui->doubleSpinBox_meshingTextureMaxDepthError->value()).toDouble());
500  _ui->doubleSpinBox_meshingTextureMaxAngle->setValue(settings.value("mesh_textureMaxAngle", _ui->doubleSpinBox_meshingTextureMaxAngle->value()).toDouble());
501  _ui->spinBox_mesh_minTextureClusterSize->setValue(settings.value("mesh_textureMinCluster", _ui->spinBox_mesh_minTextureClusterSize->value()).toDouble());
502  _ui->lineEdit_meshingTextureRoiRatios->setText(settings.value("mesh_textureRoiRatios", _ui->lineEdit_meshingTextureRoiRatios->text()).toString());
503  _ui->checkBox_cameraFilter->setChecked(settings.value("mesh_textureCameraFiltering", _ui->checkBox_cameraFilter->isChecked()).toBool());
504  _ui->doubleSpinBox_cameraFilterRadius->setValue(settings.value("mesh_textureCameraFilteringRadius", _ui->doubleSpinBox_cameraFilterRadius->value()).toDouble());
505  _ui->doubleSpinBox_cameraFilterAngle->setValue(settings.value("mesh_textureCameraFilteringAngle", _ui->doubleSpinBox_cameraFilterAngle->value()).toDouble());
506  _ui->doubleSpinBox_cameraFilterVel->setValue(settings.value("mesh_textureCameraFilteringVel", _ui->doubleSpinBox_cameraFilterVel->value()).toDouble());
507  _ui->doubleSpinBox_cameraFilterVelRad->setValue(settings.value("mesh_textureCameraFilteringVelRad", _ui->doubleSpinBox_cameraFilterVelRad->value()).toDouble());
508  _ui->doubleSpinBox_laplacianVariance->setValue(settings.value("mesh_textureCameraFilteringLaplacian", _ui->doubleSpinBox_laplacianVariance->value()).toDouble());
509  _ui->spinBox_textureBrightnessContrastRatioLow->setValue(settings.value("mesh_textureBrightnessConstrastRatioLow", _ui->spinBox_textureBrightnessContrastRatioLow->value()).toDouble());
510  _ui->spinBox_textureBrightnessContrastRatioHigh->setValue(settings.value("mesh_textureBrightnessConstrastRatioHigh", _ui->spinBox_textureBrightnessContrastRatioHigh->value()).toDouble());
511  if(_ui->checkBox_exposureFusion->isEnabled())
512  {
513  _ui->checkBox_exposureFusion->setChecked(settings.value("mesh_textureExposureFusion", _ui->checkBox_exposureFusion->isChecked()).toBool());
514  }
515  _ui->checkBox_blending->setChecked(settings.value("mesh_textureBlending", _ui->checkBox_blending->isChecked()).toBool());
516  _ui->comboBox_blendingDecimation->setCurrentIndex(settings.value("mesh_textureBlendingDecimation", _ui->comboBox_blendingDecimation->currentIndex()).toInt());
517 
518  _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value("mesh_angle_tolerance", _ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
519  _ui->checkBox_mesh_quad->setChecked(settings.value("mesh_quad", _ui->checkBox_mesh_quad->isChecked()).toBool());
520  _ui->spinBox_mesh_triangleSize->setValue(settings.value("mesh_triangle_size", _ui->spinBox_mesh_triangleSize->value()).toInt());
521 
522  _ui->checkBox_poisson_outputPolygons->setChecked(settings.value("poisson_outputPolygons", _ui->checkBox_poisson_outputPolygons->isChecked()).toBool());
523  _ui->checkBox_poisson_manifold->setChecked(settings.value("poisson_manifold", _ui->checkBox_poisson_manifold->isChecked()).toBool());
524  _ui->spinBox_poisson_depth->setValue(settings.value("poisson_depth", _ui->spinBox_poisson_depth->value()).toInt());
525  _ui->spinBox_poisson_iso->setValue(settings.value("poisson_iso", _ui->spinBox_poisson_iso->value()).toInt());
526  _ui->spinBox_poisson_solver->setValue(settings.value("poisson_solver", _ui->spinBox_poisson_solver->value()).toInt());
527  _ui->spinBox_poisson_minDepth->setValue(settings.value("poisson_minDepth", _ui->spinBox_poisson_minDepth->value()).toInt());
528  _ui->doubleSpinBox_poisson_samples->setValue(settings.value("poisson_samples", _ui->doubleSpinBox_poisson_samples->value()).toDouble());
529  _ui->doubleSpinBox_poisson_pointWeight->setValue(settings.value("poisson_pointWeight", _ui->doubleSpinBox_poisson_pointWeight->value()).toDouble());
530  _ui->doubleSpinBox_poisson_scale->setValue(settings.value("poisson_scale", _ui->doubleSpinBox_poisson_scale->value()).toDouble());
531 
532  _ui->doubleSpinBox_cputsdf_size->setValue(settings.value("cputsdf_size", _ui->doubleSpinBox_cputsdf_size->value()).toDouble());
533  _ui->doubleSpinBox_cputsdf_resolution->setValue(settings.value("cputsdf_resolution", _ui->doubleSpinBox_cputsdf_resolution->value()).toDouble());
534  _ui->doubleSpinBox_cputsdf_tuncPos->setValue(settings.value("cputsdf_truncPos", _ui->doubleSpinBox_cputsdf_tuncPos->value()).toDouble());
535  _ui->doubleSpinBox_cputsdf_tuncNeg->setValue(settings.value("cputsdf_truncNeg", _ui->doubleSpinBox_cputsdf_tuncNeg->value()).toDouble());
536  _ui->doubleSpinBox_cputsdf_minWeight->setValue(settings.value("cputsdf_minWeight", _ui->doubleSpinBox_cputsdf_minWeight->value()).toDouble());
537  _ui->doubleSpinBox_cputsdf_flattenRadius->setValue(settings.value("cputsdf_flattenRadius", _ui->doubleSpinBox_cputsdf_flattenRadius->value()).toDouble());
538  _ui->spinBox_cputsdf_randomSplit->setValue(settings.value("cputsdf_randomSplit", _ui->spinBox_cputsdf_randomSplit->value()).toInt());
539 
540  _ui->checkBox_openchisel_mergeVertices->setChecked(settings.value("openchisel_merge_vertices", _ui->checkBox_openchisel_mergeVertices->isChecked()).toBool());
541  _ui->spinBox_openchisel_chunk_size_x->setValue(settings.value("openchisel_chunk_size_x", _ui->spinBox_openchisel_chunk_size_x->value()).toInt());
542  _ui->spinBox_openchisel_chunk_size_y->setValue(settings.value("openchisel_chunk_size_y", _ui->spinBox_openchisel_chunk_size_y->value()).toInt());
543  _ui->spinBox_openchisel_chunk_size_z->setValue(settings.value("openchisel_chunk_size_z", _ui->spinBox_openchisel_chunk_size_z->value()).toInt());
544  _ui->doubleSpinBox_openchisel_truncation_constant->setValue(settings.value("openchisel_truncation_constant", _ui->doubleSpinBox_openchisel_truncation_constant->value()).toDouble());
545  _ui->doubleSpinBox_openchisel_truncation_linear->setValue(settings.value("openchisel_truncation_linear", _ui->doubleSpinBox_openchisel_truncation_linear->value()).toDouble());
546  _ui->doubleSpinBox_openchisel_truncation_quadratic->setValue(settings.value("openchisel_truncation_quadratic", _ui->doubleSpinBox_openchisel_truncation_quadratic->value()).toDouble());
547  _ui->doubleSpinBox_openchisel_truncation_scale->setValue(settings.value("openchisel_truncation_scale", _ui->doubleSpinBox_openchisel_truncation_scale->value()).toDouble());
548  _ui->spinBox_openchisel_integration_weight->setValue(settings.value("openchisel_integration_weight", _ui->spinBox_openchisel_integration_weight->value()).toInt());
549  _ui->checkBox_openchisel_use_voxel_carving->setChecked(settings.value("openchisel_use_voxel_carving", _ui->checkBox_openchisel_use_voxel_carving->isChecked()).toBool());
550  _ui->doubleSpinBox_openchisel_carving_dist_m->setValue(settings.value("openchisel_carving_dist_m", _ui->doubleSpinBox_openchisel_carving_dist_m->value()).toDouble());
551  _ui->doubleSpinBox_openchisel_near_plane_dist->setValue(settings.value("openchisel_near_plane_dist", _ui->doubleSpinBox_openchisel_near_plane_dist->value()).toDouble());
552  _ui->doubleSpinBox_openchisel_far_plane_dist->setValue(settings.value("openchisel_far_plane_dist", _ui->doubleSpinBox_openchisel_far_plane_dist->value()).toDouble());
553 
556 
557  if(!group.isEmpty())
558  {
559  settings.endGroup();
560  }
561 }
562 
564 {
565  _ui->comboBox_pipeline->setCurrentIndex(1);
566  _ui->checkBox_fromDepth->setChecked(true);
567  _ui->checkBox_binary->setChecked(true);
568  _ui->spinBox_normalKSearch->setValue(20);
569  _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
570 
571  _ui->checkBox_regenerate->setChecked(_dbDriver!=0?true:false);
572  _ui->spinBox_decimation->setValue(1);
573  _ui->doubleSpinBox_maxDepth->setValue(4);
574  _ui->doubleSpinBox_minDepth->setValue(0);
575  _ui->spinBox_fillDepthHoles->setValue(0);
576  _ui->spinBox_fillDepthHolesError->setValue(2);
577  _ui->lineEdit_roiRatios->setText("0.0 0.0 0.0 0.0");
578  _ui->lineEdit_distortionModel->setText("");
579 
580  _ui->checkBox_bilateral->setChecked(false);
581  _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
582  _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
583 
584  _ui->checkBox_filtering->setChecked(false);
585  _ui->doubleSpinBox_filteringRadius->setValue(0.02);
586  _ui->spinBox_filteringMinNeighbors->setValue(2);
587 
588  _ui->checkBox_assemble->setChecked(true);
589  _ui->doubleSpinBox_voxelSize_assembled->setValue(0.01);
590  _ui->comboBox_frame->setCurrentIndex(0);
591 
592  _ui->checkBox_subtraction->setChecked(false);
593  _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(0.02);
594  _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(0);
595  _ui->spinBox_subtractFilteringMinPts->setValue(5);
596 
597  _ui->checkBox_smoothing->setChecked(false);
598  _ui->doubleSpinBox_mlsRadius->setValue(0.04);
599  _ui->spinBox_polygonialOrder->setValue(2);
600  _ui->comboBox_upsamplingMethod->setCurrentIndex(0);
601  _ui->doubleSpinBox_sampleRadius->setValue(0.01);
602  _ui->doubleSpinBox_sampleStep->setValue(0.005);
603  _ui->spinBox_randomPoints->setValue(10);
604  _ui->doubleSpinBox_dilationVoxelSize->setValue(0.005);
605  _ui->spinBox_dilationSteps->setValue(1);
606  _ui->doubleSpinBox_mls_outputVoxelSize->setValue(0);
607 
608  _ui->checkBox_gainCompensation->setChecked(false);
609  _ui->doubleSpinBox_gainRadius->setValue(0.02);
610  _ui->doubleSpinBox_gainOverlap->setValue(0.0);
611  _ui->doubleSpinBox_gainBeta->setValue(10);
612  _ui->checkBox_gainRGB->setChecked(true);
613  _ui->checkBox_gainFull->setChecked(false);
614 
615  _ui->checkBox_meshing->setChecked(false);
616  _ui->doubleSpinBox_gp3Radius->setValue(0.2);
617  _ui->doubleSpinBox_gp3Mu->setValue(2.5);
618  _ui->doubleSpinBox_meshDecimationFactor->setValue(0.0);
619  _ui->spinBox_meshMaxPolygons->setValue(0);
620  _ui->doubleSpinBox_transferColorRadius->setValue(0.025);
621  _ui->checkBox_cleanMesh->setChecked(true);
622  _ui->spinBox_mesh_minClusterSize->setValue(0);
623 
624  _ui->comboBox_meshingApproach->setCurrentIndex(1);
625 
626  _ui->checkBox_textureMapping->setChecked(false);
627  _ui->comboBox_meshingTextureFormat->setCurrentIndex(0);
628  _ui->comboBox_meshingTextureSize->setCurrentIndex(5); // 4096
629  _ui->spinBox_mesh_maxTextures->setValue(1);
630  _ui->doubleSpinBox_meshingTextureMaxDistance->setValue(3.0);
631  _ui->doubleSpinBox_meshingTextureMaxDepthError->setValue(0.0);
632  _ui->doubleSpinBox_meshingTextureMaxAngle->setValue(0.0);
633  _ui->spinBox_mesh_minTextureClusterSize->setValue(50);
634  _ui->lineEdit_meshingTextureRoiRatios->setText("0.0 0.0 0.0 0.0");
635  _ui->checkBox_cameraFilter->setChecked(false);
636  _ui->doubleSpinBox_cameraFilterRadius->setValue(0);
637  _ui->doubleSpinBox_cameraFilterAngle->setValue(30);
638  _ui->doubleSpinBox_cameraFilterVel->setValue(0);
639  _ui->doubleSpinBox_cameraFilterVelRad->setValue(0);
640  _ui->doubleSpinBox_laplacianVariance->setValue(0);
641  _ui->spinBox_textureBrightnessContrastRatioLow->setValue(0);
642  _ui->spinBox_textureBrightnessContrastRatioHigh->setValue(0);
643  _ui->checkBox_exposureFusion->setChecked(false);
644  _ui->checkBox_blending->setChecked(true);
645  _ui->comboBox_blendingDecimation->setCurrentIndex(0);
646 
647  _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
648  _ui->checkBox_mesh_quad->setChecked(false);
649  _ui->spinBox_mesh_triangleSize->setValue(1);
650 
651  _ui->checkBox_poisson_outputPolygons->setChecked(false);
652  _ui->checkBox_poisson_manifold->setChecked(true);
653  _ui->spinBox_poisson_depth->setValue(0);
654  _ui->spinBox_poisson_iso->setValue(8);
655  _ui->spinBox_poisson_solver->setValue(8);
656  _ui->spinBox_poisson_minDepth->setValue(5);
657  _ui->doubleSpinBox_poisson_samples->setValue(1.0);
658  _ui->doubleSpinBox_poisson_pointWeight->setValue(4.0);
659  _ui->doubleSpinBox_poisson_scale->setValue(1.1);
660 
661  _ui->doubleSpinBox_cputsdf_size->setValue(12.0);
662  _ui->doubleSpinBox_cputsdf_resolution->setValue(0.01);
663  _ui->doubleSpinBox_cputsdf_tuncPos->setValue(0.03);
664  _ui->doubleSpinBox_cputsdf_tuncNeg->setValue(0.03);
665  _ui->doubleSpinBox_cputsdf_minWeight->setValue(0);
666  _ui->doubleSpinBox_cputsdf_flattenRadius->setValue(0.005);
667  _ui->spinBox_cputsdf_randomSplit->setValue(1);
668 
669  _ui->checkBox_openchisel_mergeVertices->setChecked(true);
670  _ui->spinBox_openchisel_chunk_size_x->setValue(16);
671  _ui->spinBox_openchisel_chunk_size_y->setValue(16);
672  _ui->spinBox_openchisel_chunk_size_z->setValue(16);
673  _ui->doubleSpinBox_openchisel_truncation_constant->setValue(0.001504);
674  _ui->doubleSpinBox_openchisel_truncation_linear->setValue(0.00152);
675  _ui->doubleSpinBox_openchisel_truncation_quadratic->setValue(0.0019);
676  _ui->doubleSpinBox_openchisel_truncation_scale->setValue(10.0);
677  _ui->spinBox_openchisel_integration_weight->setValue(1);
678  _ui->checkBox_openchisel_use_voxel_carving->setChecked(false);
679  _ui->doubleSpinBox_openchisel_carving_dist_m->setValue(0.05);
680  _ui->doubleSpinBox_openchisel_near_plane_dist->setValue(0.05);
681  _ui->doubleSpinBox_openchisel_far_plane_dist->setValue(1.1);
682 
683 
686 
687  this->update();
688 }
689 
691 {
692  QString path = QFileDialog::getOpenFileName(this, tr("Load Settings"), _workingDirectory, tr("Config (*.ini)"));
693  if(path.size())
694  {
695  QSettings settings(path, QSettings::IniFormat);
696  settings.beginGroup("Gui");
697  settings.beginGroup(this->objectName());
698  this->loadSettings(settings);
699  settings.endGroup(); // "name"
700  settings.endGroup(); // Gui
701  }
702 }
703 
705 {
706  QString path = QFileDialog::getSaveFileName(this, tr("Save Settings"), _workingDirectory, tr("Config (*.ini)"));
707  if(path.size())
708  {
709  QSettings settings(path, QSettings::IniFormat);
710  settings.beginGroup("Gui");
711  settings.beginGroup(this->objectName());
712  this->saveSettings(settings);
713  settings.endGroup(); // "name"
714  settings.endGroup(); // Gui
715  }
716 }
717 
719 {
720  if(!_ui->checkBox_fromDepth->isChecked())
721  {
722  _ui->comboBox_pipeline->setCurrentIndex(1);
723  _ui->comboBox_pipeline->setEnabled(false);
724  _ui->comboBox_frame->setItemData(2, 0,Qt::UserRole - 1);
725  _ui->comboBox_frame->setItemData(3, 1|32,Qt::UserRole - 1);
726  if(_ui->comboBox_frame->currentIndex() == 2)
727  {
728  _ui->comboBox_frame->setCurrentIndex(0);
729  }
730  }
731  else
732  {
733  _ui->comboBox_pipeline->setEnabled(true);
734  _ui->comboBox_frame->setItemData(2, 1|32,Qt::UserRole - 1);
735  _ui->comboBox_frame->setItemData(3, 0,Qt::UserRole - 1);
736  if(_ui->comboBox_frame->currentIndex() == 3)
737  {
738  _ui->comboBox_frame->setCurrentIndex(0);
739  }
740  }
741 
742  _ui->checkBox_smoothing->setVisible(_ui->comboBox_pipeline->currentIndex() == 1);
743  _ui->checkBox_smoothing->setEnabled(_ui->comboBox_pipeline->currentIndex() == 1);
744  _ui->label_smoothing->setVisible(_ui->comboBox_pipeline->currentIndex() == 1);
745 
746  _ui->comboBox_frame->setEnabled(!_ui->checkBox_assemble->isChecked() && _ui->checkBox_binary->isEnabled());
747  _ui->comboBox_frame->setVisible(_ui->comboBox_frame->isEnabled());
748  _ui->label_frame->setVisible(_ui->comboBox_frame->isEnabled());
749  _ui->checkBox_gainCompensation->setEnabled(!(_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex() == 2));
750  _ui->checkBox_gainCompensation->setVisible(_ui->checkBox_gainCompensation->isEnabled());
751  _ui->label_gainCompensation->setVisible(_ui->checkBox_gainCompensation->isEnabled());
752 
753  _ui->groupBox_regenerate->setVisible(_ui->checkBox_regenerate->isChecked() && _ui->checkBox_fromDepth->isChecked());
754  _ui->groupBox_regenerateScans->setVisible(_ui->checkBox_regenerate->isChecked() && !_ui->checkBox_fromDepth->isChecked());
755  _ui->groupBox_bilateral->setVisible(_ui->checkBox_bilateral->isChecked());
756  _ui->groupBox_filtering->setVisible(_ui->checkBox_filtering->isChecked());
757  _ui->groupBox_gain->setVisible(_ui->checkBox_gainCompensation->isEnabled() && _ui->checkBox_gainCompensation->isChecked());
758  _ui->groupBox_mls->setVisible(_ui->checkBox_smoothing->isEnabled() && _ui->checkBox_smoothing->isChecked());
759  _ui->groupBox_meshing->setVisible(_ui->checkBox_meshing->isChecked());
760  _ui->groupBox_subtraction->setVisible(_ui->checkBox_subtraction->isChecked());
761  _ui->groupBox_textureMapping->setVisible(_ui->checkBox_textureMapping->isChecked());
762  _ui->groupBox_cameraFilter->setVisible(_ui->checkBox_cameraFilter->isChecked());
763 
764  // dense texturing options
765  if(_ui->checkBox_meshing->isChecked())
766  {
767  //GP3
768  _ui->comboBox_meshingApproach->setItemData(0, _ui->comboBox_pipeline->currentIndex() == 1?1 | 32:0,Qt::UserRole - 1);
769 
770  //Poisson
771  _ui->comboBox_meshingApproach->setItemData(1, _ui->comboBox_pipeline->currentIndex() == 1 && _ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
772 
773  //CPU-TSDF
774 #ifdef RTABMAP_CPUTSDF
775  _ui->comboBox_meshingApproach->setItemData(2, _ui->comboBox_pipeline->currentIndex() == 0 && _ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
776 #else
777  _ui->comboBox_meshingApproach->setItemData(2, 0, Qt::UserRole - 1);
778 #endif
779 
780  // Organized
781  _ui->comboBox_meshingApproach->setItemData(3, _ui->comboBox_pipeline->currentIndex() == 0?1 | 32:0,Qt::UserRole - 1);
782 
783  //Open Chisel
784 #ifdef RTABMAP_OPENCHISEL
785  _ui->comboBox_meshingApproach->setItemData(4, _ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
786 #else
787  _ui->comboBox_meshingApproach->setItemData(4, 0, Qt::UserRole - 1);
788 #endif
789 
790  if(_ui->comboBox_pipeline->currentIndex() == 0 && _ui->comboBox_meshingApproach->currentIndex()<2)
791  {
792  _ui->comboBox_meshingApproach->setCurrentIndex(3);
793  }
794  if(_ui->comboBox_pipeline->currentIndex() == 1 && (_ui->comboBox_meshingApproach->currentIndex()==2 || _ui->comboBox_meshingApproach->currentIndex()==3))
795  {
796  _ui->comboBox_meshingApproach->setCurrentIndex(1);
797  }
798  if(!_ui->checkBox_assemble->isChecked())
799  {
800  _ui->comboBox_meshingApproach->setCurrentIndex(_ui->comboBox_pipeline->currentIndex() == 1?0:3);
801  }
802 
803  _ui->checkBox_poisson_outputPolygons->setDisabled(
804  _ui->checkBox_binary->isEnabled() ||
805  _ui->doubleSpinBox_meshDecimationFactor->value()!=0.0 ||
806  _ui->spinBox_meshMaxPolygons->value()!=0 ||
807  _ui->checkBox_textureMapping->isChecked());
808 
809  _ui->checkBox_cleanMesh->setEnabled(_ui->comboBox_pipeline->currentIndex() == 1);
810  _ui->label_meshClean->setEnabled(_ui->comboBox_pipeline->currentIndex() == 1);
811 
812  _ui->groupBox_gp3->setVisible(_ui->comboBox_pipeline->currentIndex() == 1 && _ui->comboBox_meshingApproach->currentIndex()==0);
813  _ui->groupBox_poisson->setVisible(_ui->comboBox_pipeline->currentIndex() == 1 && _ui->comboBox_meshingApproach->currentIndex()==1);
814  _ui->groupBox_cputsdf->setVisible(_ui->comboBox_pipeline->currentIndex() == 0 && _ui->comboBox_meshingApproach->currentIndex()==2);
815  _ui->groupBox_organized->setVisible(_ui->comboBox_pipeline->currentIndex() == 0 && _ui->comboBox_meshingApproach->currentIndex()==3);
816  _ui->groupBox_openchisel->setVisible(_ui->comboBox_meshingApproach->currentIndex()==4);
817 
818 #ifndef DISABLE_VTK
819  _ui->doubleSpinBox_meshDecimationFactor->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
820  _ui->label_meshDecimation->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
821  _ui->spinBox_meshMaxPolygons->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
822  _ui->label_meshMaxPolygons->setEnabled(_ui->comboBox_meshingApproach->currentIndex()!=3);
823 #endif
824  }
825 }
826 
828 {
829  QString dir = _ui->lineEdit_distortionModel->text();
830  if(dir.isEmpty())
831  {
832  dir = _workingDirectory;
833  }
834  QString path = QFileDialog::getOpenFileName(this, tr("Select file"), dir, tr("Distortion model (*.bin *.txt)"));
835  if(path.size())
836  {
837  _ui->lineEdit_distortionModel->setText(path);
838  }
839 }
840 
842 {
843  _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(false);
844  _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(true);
845  _ui->checkBox_binary->setVisible(true);
846  _ui->checkBox_binary->setEnabled(true);
847  _ui->label_binaryFile->setVisible(true);
848  _ui->checkBox_mesh_quad->setVisible(false);
849  _ui->checkBox_mesh_quad->setEnabled(false);
850  _ui->label_quad->setVisible(false);
852 }
853 
855 {
856  _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(true);
857  _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(false);
858  _ui->checkBox_binary->setVisible(false);
859  _ui->checkBox_binary->setEnabled(false);
860  _ui->label_binaryFile->setVisible(false);
861  _ui->checkBox_mesh_quad->setVisible(true);
862  _ui->checkBox_mesh_quad->setEnabled(true);
863  _ui->label_quad->setVisible(true);
865 }
866 
868  const std::map<int, Transform> & poses,
869  const std::multimap<int, Link> & links,
870  const std::map<int, int> & mapIds,
871  const QMap<int, Signature> & cachedSignatures,
872  const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
873  const std::map<int, LaserScan> & cachedScans,
874  const QString & workingDirectory,
875  const ParametersMap & parameters)
876 {
877  std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
878  std::map<int, pcl::PolygonMesh::Ptr> meshes;
879  std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
880  std::vector<std::map<int, pcl::PointXY> > textureVertexToPixels;
881 
882  setSaveButton();
883 
885  poses,
886  links,
887  mapIds,
888  cachedSignatures,
889  cachedClouds,
890  cachedScans,
891  workingDirectory,
892  parameters,
893  clouds,
894  meshes,
895  textureMeshes,
896  textureVertexToPixels))
897  {
898  if(textureMeshes.size())
899  {
900  saveTextureMeshes(workingDirectory, poses, textureMeshes, cachedSignatures, textureVertexToPixels);
901  }
902  else if(meshes.size())
903  {
904  bool exportMeshes = true;
905  if(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked())
906  {
907  QMessageBox::StandardButton r = QMessageBox::warning(this, tr("Exporting Texture Mesh"),
908  tr("No texture mesh could be created, do you want to continue with saving only the meshes (%1)?").arg(meshes.size()),
909  QMessageBox::Yes|QMessageBox::No, QMessageBox::Yes);
910  exportMeshes = r == QMessageBox::Yes;
911  }
912  if(exportMeshes)
913  {
914  saveMeshes(workingDirectory, poses, meshes, _ui->checkBox_binary->isChecked());
915  }
916  }
917  else
918  {
919  saveClouds(workingDirectory, poses, clouds, _ui->checkBox_binary->isChecked());
920  }
921  }
922  else if(!_canceled)
923  {
925  }
927 }
928 
930  const std::map<int, Transform> & poses,
931  const std::multimap<int, Link> & links,
932  const std::map<int, int> & mapIds,
933  const QMap<int, Signature> & cachedSignatures,
934  const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
935  const std::map<int, LaserScan> & cachedScans,
936  const QString & workingDirectory,
937  const ParametersMap & parameters)
938 {
939  std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
940  std::map<int, pcl::PolygonMesh::Ptr> meshes;
941  std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
942  std::vector<std::map<int, pcl::PointXY> > textureVertexToPixels;
943 
944  setOkButton();
945 
947  poses,
948  links,
949  mapIds,
950  cachedSignatures,
951  cachedClouds,
952  cachedScans,
953  workingDirectory,
954  parameters,
955  clouds,
956  meshes,
957  textureMeshes,
958  textureVertexToPixels))
959  {
960  QDialog * window = new QDialog(this->parentWidget()?this->parentWidget():this, Qt::Window);
961  window->setAttribute(Qt::WA_DeleteOnClose, true);
962  if(meshes.size())
963  {
964  window->setWindowTitle(tr("Meshes (%1 nodes)").arg(meshes.size()));
965  }
966  else
967  {
968  window->setWindowTitle(tr("Clouds (%1 nodes)").arg(clouds.size()));
969  }
970  window->setMinimumWidth(120);
971  window->setMinimumHeight(90);
972  window->resize(QDesktopWidget().availableGeometry(this).size() * 0.7);
973 
974  CloudViewer * viewer = new CloudViewer(window);
975  if(_ui->comboBox_pipeline->currentIndex() == 0)
976  {
977  viewer->setBackfaceCulling(true, false);
978  }
979  viewer->setLighting(true);
980  viewer->setDefaultBackgroundColor(QColor(40, 40, 40, 255));
981  viewer->buildPickingLocator(true);
982 
983  QVBoxLayout *layout = new QVBoxLayout();
984  layout->addWidget(viewer);
985  layout->setContentsMargins(0,0,0,0);
986  window->setLayout(layout);
987  connect(window, SIGNAL(finished(int)), viewer, SLOT(clear()));
988 
989  window->show();
990 
991  _progressDialog->appendText(tr("Opening visualizer..."));
992  QApplication::processEvents();
993  uSleep(500);
994  QApplication::processEvents();
995 
996  if(textureMeshes.size())
997  {
998  viewer->setPolygonPicking(true);
999  std::map<int, cv::Mat> images;
1000  std::map<int, std::vector<CameraModel> > calibrations;
1001  for(QMap<int, Signature>::const_iterator iter=cachedSignatures.constBegin(); iter!=cachedSignatures.constEnd(); ++iter)
1002  {
1003  std::vector<CameraModel> models;
1004  if(iter->sensorData().cameraModels().size())
1005  {
1006  models = iter->sensorData().cameraModels();
1007  }
1008  else if(iter->sensorData().stereoCameraModel().isValidForProjection())
1009  {
1010  models.push_back(iter->sensorData().stereoCameraModel().left());
1011  }
1012 
1013  if(!models.empty())
1014  {
1015  if(!iter->sensorData().imageRaw().empty())
1016  {
1017  calibrations.insert(std::make_pair(iter.key(), models));
1018  images.insert(std::make_pair(iter.key(), iter->sensorData().imageRaw()));
1019  }
1020  else if(!iter->sensorData().imageCompressed().empty())
1021  {
1022  calibrations.insert(std::make_pair(iter.key(), models));
1023  images.insert(std::make_pair(iter.key(), iter->sensorData().imageCompressed()));
1024  }
1025  }
1026  }
1027  int textureSize = 1024;
1028  if(_ui->comboBox_meshingTextureSize->currentIndex() > 0)
1029  {
1030  textureSize = 128 << _ui->comboBox_meshingTextureSize->currentIndex(); // start at 256
1031  }
1032  int blendingDecimation = 0;
1033  if(_ui->checkBox_blending->isChecked())
1034  {
1035  if(_ui->comboBox_blendingDecimation->currentIndex() > 0)
1036  {
1037  blendingDecimation = 1 << (_ui->comboBox_blendingDecimation->currentIndex()-1);
1038  }
1039  }
1040 
1041  for (std::map<int, pcl::TextureMesh::Ptr>::iterator iter = textureMeshes.begin(); iter != textureMeshes.end(); ++iter)
1042  {
1043  pcl::TextureMesh::Ptr mesh = iter->second;
1044 
1045  // As CloudViewer is not supporting more than one texture per mesh, merge them all by default
1046  cv::Mat globalTexture;
1047  if (mesh->tex_materials.size() > 1)
1048  {
1049  cv::Mat globalTextures;
1050  globalTextures = util3d::mergeTextures(
1051  *mesh,
1052  images,
1053  calibrations,
1054  0,
1055  _dbDriver,
1056  textureSize,
1057  1,
1058  textureVertexToPixels,
1059  _ui->checkBox_gainCompensation->isChecked(),
1060  _ui->doubleSpinBox_gainBeta->value(),
1061  _ui->checkBox_gainRGB->isChecked(),
1062  _ui->checkBox_blending->isChecked(),
1063  blendingDecimation,
1064  _ui->spinBox_textureBrightnessContrastRatioLow->value(),
1065  _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
1066  _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked());
1067  if(globalTextures.rows == globalTextures.cols)
1068  {
1069  globalTexture = globalTextures;
1070  }
1071  }
1072 
1073  _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)...").arg(iter->first).arg(mesh->tex_polygons.size()?mesh->tex_polygons[0].size():0));
1075 
1076  // VTK issue:
1077  // tex_coordinates should be linked to points, not
1078  // polygon vertices. Points linked to multiple different TCoords (different textures) should
1079  // be duplicated.
1080  for (unsigned int t = 0; t < mesh->tex_coordinates.size(); ++t)
1081  {
1082  if(mesh->tex_polygons[t].size())
1083  {
1084 
1085  pcl::PointCloud<pcl::PointXYZ>::Ptr originalCloud(new pcl::PointCloud<pcl::PointXYZ>);
1086  pcl::fromPCLPointCloud2(mesh->cloud, *originalCloud);
1087 
1088  // make a cloud with as many points than polygon vertices
1089  unsigned int nPoints = mesh->tex_coordinates[t].size();
1090  UASSERT(nPoints == mesh->tex_polygons[t].size()*mesh->tex_polygons[t][0].vertices.size()); // assuming polygon size is constant!
1091 
1092  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
1093  cloud->resize(nPoints);
1094 
1095  unsigned int oi = 0;
1096  for (unsigned int i = 0; i < mesh->tex_polygons[t].size(); ++i)
1097  {
1098  pcl::Vertices & vertices = mesh->tex_polygons[t][i];
1099 
1100  for(unsigned int j=0; j<vertices.vertices.size(); ++j)
1101  {
1102  UASSERT(oi < cloud->size());
1103  UASSERT_MSG(vertices.vertices[j] < originalCloud->size(), uFormat("%d vs %d", vertices.vertices[j], (int)originalCloud->size()).c_str());
1104  cloud->at(oi) = originalCloud->at(vertices.vertices[j]);
1105  vertices.vertices[j] = oi; // new vertice index
1106  ++oi;
1107  }
1108  }
1109  pcl::toPCLPointCloud2(*cloud, mesh->cloud);
1110  }
1111  else
1112  {
1113  UWARN("No polygons for texture %d of mesh %d?!", t, iter->first);
1114  }
1115  }
1116 
1117  if (globalTexture.empty())
1118  {
1119  if(mesh->tex_materials.size()==1 &&
1120  !mesh->tex_materials[0].tex_file.empty() &&
1121  uIsInteger(mesh->tex_materials[0].tex_file, false))
1122  {
1123  int textureId = uStr2Int(mesh->tex_materials[0].tex_file);
1124  SensorData data;
1125  if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
1126  {
1127  data = cachedSignatures.value(textureId).sensorData();
1128  }
1129  else if(_dbDriver)
1130  {
1131  _dbDriver->getNodeData(textureId, data, true, false, false, false);
1132  }
1133  UASSERT(!data.imageCompressed().empty());
1134  data.uncompressDataConst(&globalTexture, 0);
1135  UASSERT(!globalTexture.empty());
1136  if (_ui->checkBox_gainCompensation->isChecked() && _compensator && _compensator->getIndex(textureId) >= 0)
1137  {
1138  _compensator->apply(textureId, globalTexture, _ui->checkBox_gainRGB->isChecked());
1139  }
1140  }
1141  else
1142  {
1143  _progressDialog->appendText(tr("No textures added to mesh %1!?").arg(iter->first), Qt::darkRed);
1144  _progressDialog->setAutoClose(false);
1145  }
1146  }
1147 
1148  viewer->addCloudTextureMesh(uFormat("mesh%d",iter->first), mesh, globalTexture, iter->first>0?poses.at(iter->first):Transform::getIdentity());
1149  _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)... done.").arg(iter->first).arg(mesh->tex_polygons.size()?mesh->tex_polygons[0].size():0));
1150  QApplication::processEvents();
1151  }
1152  }
1153  else if(meshes.size())
1154  {
1155  viewer->setPolygonPicking(true);
1156  for(std::map<int, pcl::PolygonMesh::Ptr>::iterator iter = meshes.begin(); iter!=meshes.end(); ++iter)
1157  {
1158  _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)...").arg(iter->first).arg(iter->second->polygons.size()));
1160  bool isRGB = false;
1161  for(unsigned int i=0; i<iter->second->cloud.fields.size(); ++i)
1162  {
1163  if(iter->second->cloud.fields[i].name.compare("rgb") == 0)
1164  {
1165  isRGB=true;
1166  break;
1167  }
1168  }
1169  if(isRGB)
1170  {
1171  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
1172  pcl::fromPCLPointCloud2(iter->second->cloud, *cloud);
1173  viewer->addCloudMesh(uFormat("mesh%d",iter->first), cloud, iter->second->polygons, iter->first>0?poses.at(iter->first):Transform::getIdentity());
1174  }
1175  else
1176  {
1177  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
1178  pcl::fromPCLPointCloud2(iter->second->cloud, *cloud);
1179  viewer->addCloudMesh(uFormat("mesh%d",iter->first), cloud, iter->second->polygons, iter->first>0?poses.at(iter->first):Transform::getIdentity());
1180  }
1181  _progressDialog->appendText(tr("Viewing the mesh %1 (%2 polygons)... done.").arg(iter->first).arg(iter->second->polygons.size()));
1182  QApplication::processEvents();
1183  }
1184  }
1185  else if(clouds.size())
1186  {
1187  for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::iterator iter = clouds.begin(); iter!=clouds.end(); ++iter)
1188  {
1189  _progressDialog->appendText(tr("Viewing the cloud %1 (%2 points)...").arg(iter->first).arg(iter->second->size()));
1191 
1192  QColor color = Qt::gray;
1193  int mapId = uValue(mapIds, iter->first, -1);
1194  if(mapId >= 0)
1195  {
1196  color = (Qt::GlobalColor)(mapId % 12 + 7 );
1197  }
1198  viewer->addCloud(uFormat("cloud%d",iter->first), iter->second, iter->first>0?poses.at(iter->first):Transform::getIdentity());
1199  viewer->setCloudPointSize(uFormat("cloud%d",iter->first), 2);
1200  _progressDialog->appendText(tr("Viewing the cloud %1 (%2 points)... done.").arg(iter->first).arg(iter->second->size()));
1201  }
1202  }
1203  viewer->update();
1204  }
1205  else
1206  {
1207  _progressDialog->setAutoClose(false);
1208  }
1210 }
1211 
1213 {
1214  int textureSize = 1024;
1215  if(_ui->comboBox_meshingTextureSize->currentIndex() > 0)
1216  {
1217  textureSize = 128 << _ui->comboBox_meshingTextureSize->currentIndex(); // start at 256
1218  }
1219  return textureSize;
1220 }
1222 {
1223  return _ui->spinBox_mesh_maxTextures->value();
1224 }
1226 {
1227  return _ui->checkBox_gainCompensation->isChecked();
1228 }
1230 {
1231  return _ui->doubleSpinBox_gainBeta->value();
1232 }
1234 {
1235  return _ui->checkBox_gainRGB->isChecked();
1236 }
1238 {
1239  return _ui->checkBox_blending->isChecked();
1240 }
1242 {
1243  int blendingDecimation = 0;
1244  if(_ui->checkBox_blending->isChecked())
1245  {
1246  if(_ui->comboBox_blendingDecimation->currentIndex() > 0)
1247  {
1248  blendingDecimation = 1 << (_ui->comboBox_blendingDecimation->currentIndex()-1);
1249  }
1250  }
1251  return blendingDecimation;
1252 }
1254 {
1255  return _ui->spinBox_textureBrightnessContrastRatioLow->value();
1256 }
1258 {
1259  return _ui->spinBox_textureBrightnessContrastRatioHigh->value();
1260 }
1262 {
1263  return _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked();
1264 }
1265 
1266 bool ExportCloudsDialog::removeDirRecursively(const QString & dirName)
1267 {
1268  bool result = true;
1269  QDir dir(dirName);
1270 
1271  if (dir.exists(dirName)) {
1272  Q_FOREACH(QFileInfo info, dir.entryInfoList(QDir::NoDotAndDotDot | QDir::System | QDir::Hidden | QDir::AllDirs | QDir::Files, QDir::DirsFirst)) {
1273  if (info.isDir()) {
1274  result = removeDirRecursively(info.absoluteFilePath());
1275  }
1276  else {
1277  result = QFile::remove(info.absoluteFilePath());
1278  }
1279 
1280  if (!result) {
1281  return result;
1282  }
1283  }
1284  result = dir.rmdir(dirName);
1285  }
1286  return result;
1287 }
1288 
1290  const std::map<int, Transform> & poses,
1291  const std::multimap<int, Link> & links,
1292  const std::map<int, int> & mapIds,
1293  const QMap<int, Signature> & cachedSignatures,
1294  const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
1295  const std::map<int, LaserScan> & cachedScans,
1296  const QString & workingDirectory,
1297  const ParametersMap & parameters,
1298  std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & cloudsWithNormals,
1299  std::map<int, pcl::PolygonMesh::Ptr> & meshes,
1300  std::map<int, pcl::TextureMesh::Ptr> & textureMeshes,
1301  std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels)
1302 {
1303  _canceled = false;
1304  _workingDirectory = workingDirectory;
1305  _ui->checkBox_regenerate->setEnabled(true);
1306  if(cachedSignatures.empty() && _dbDriver)
1307  {
1308  _ui->checkBox_regenerate->setChecked(true);
1309  _ui->checkBox_regenerate->setEnabled(false);
1310  }
1311  if(_compensator)
1312  {
1313  delete _compensator;
1314  _compensator = 0;
1315  }
1316  if(this->exec() == QDialog::Accepted)
1317  {
1318  if(poses.empty())
1319  {
1320  QMessageBox::critical(this, tr("Creating clouds..."), tr("Poses are null! Cannot export/view clouds."));
1321  return false;
1322  }
1324  _progressDialog->show();
1325  int mul = 1;
1326  if(_ui->checkBox_meshing->isChecked())
1327  {
1328  mul+=1;
1329  }
1330  if(_ui->checkBox_assemble->isChecked())
1331  {
1332  mul+=1;
1333  }
1334 
1335  if(_ui->checkBox_subtraction->isChecked())
1336  {
1337  mul+=1;
1338  }
1339  if(_ui->checkBox_textureMapping->isChecked())
1340  {
1341  mul+=1;
1342  }
1343  if(_ui->checkBox_gainCompensation->isChecked())
1344  {
1345  mul+=1;
1346  }
1347  if(_ui->checkBox_mesh_quad->isEnabled()) // when enabled we are viewing the clouds
1348  {
1349  mul+=1;
1350  }
1351  _progressDialog->setMaximumSteps(int(poses.size())*mul+1);
1352 
1353  bool loadClouds = true;
1354 #ifdef RTABMAP_OPENCHISEL
1355  if(_ui->comboBox_meshingApproach->currentIndex()==4 && _ui->checkBox_assemble->isChecked())
1356  {
1357  loadClouds = !_ui->checkBox_fromDepth->isChecked();
1358  }
1359 #endif
1360 
1361  bool has2dScans = false;
1362  std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
1363  if(loadClouds)
1364  {
1365  clouds = this->getClouds(
1366  poses,
1367  cachedSignatures,
1368  cachedClouds,
1369  cachedScans,
1370  parameters,
1371  has2dScans);
1372  }
1373  else
1374  {
1375  // just create empty clouds
1376  for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
1377  {
1378  clouds.insert(std::make_pair(iter->first,
1379  std::make_pair(
1380  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr(new pcl::PointCloud<pcl::PointXYZRGBNormal>),
1381  pcl::IndicesPtr(new std::vector<int>))));
1382 
1383  }
1384  }
1385 
1386  std::set<int> validCameras = uKeysSet(clouds);
1387 
1388  UDEBUG("");
1389  if(_canceled)
1390  {
1391  return false;
1392  }
1393 
1394  if(clouds.empty())
1395  {
1396  _progressDialog->setAutoClose(false);
1397  if(_ui->checkBox_regenerate->isEnabled() && !_ui->checkBox_regenerate->isChecked())
1398  {
1399  QMessageBox::warning(this, tr("Creating clouds..."), tr("Could create clouds for %1 node(s). You "
1400  "may want to activate clouds regeneration option.").arg(poses.size()));
1401  }
1402  else
1403  {
1404  QMessageBox::warning(this, tr("Creating clouds..."), tr("Could not create clouds for %1 "
1405  "node(s). The cache may not contain point cloud data. Try re-downloading the map.").arg(poses.size()));
1406  }
1407  return false;
1408  }
1409 
1410  UDEBUG("");
1411  if(_ui->checkBox_gainCompensation->isChecked() && _ui->checkBox_fromDepth->isChecked() && clouds.size() > 1 &&
1412  // Do compensation later if we are merging textures on a dense assembled cloud
1413  !(_ui->checkBox_meshing->isChecked() &&
1414  _ui->checkBox_textureMapping->isEnabled() &&
1415  _ui->checkBox_textureMapping->isChecked() &&
1416  _ui->comboBox_pipeline->currentIndex()==1 &&
1417  _ui->checkBox_assemble->isChecked() &&
1418  _ui->comboBox_meshingTextureSize->isEnabled() &&
1419  _ui->comboBox_meshingTextureSize->currentIndex() > 0) &&
1420  // Don't do compensation if clouds are in camera frame
1421  !(_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex()==2))
1422  {
1423  UASSERT(_compensator == 0);
1424  _compensator = new GainCompensator(_ui->doubleSpinBox_gainRadius->value(), _ui->doubleSpinBox_gainOverlap->value(), 0.01, _ui->doubleSpinBox_gainBeta->value());
1425 
1426  if(_ui->checkBox_gainFull->isChecked())
1427  {
1428  _progressDialog->appendText(tr("Full gain compensation of %1 clouds...").arg(clouds.size()));
1429  }
1430  else
1431  {
1432  _progressDialog->appendText(tr("Gain compensation of %1 clouds...").arg(clouds.size()));
1433  }
1434  QApplication::processEvents();
1435  uSleep(100);
1436  QApplication::processEvents();
1437 
1438  if(_ui->checkBox_gainFull->isChecked())
1439  {
1440  std::multimap<int, Link> allLinks;
1441  for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator iter=clouds.begin(); iter!=clouds.end(); ++iter)
1442  {
1443  int from = iter->first;
1444  std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator jter = iter;
1445  ++jter;
1446  for(;jter!=clouds.end(); ++jter)
1447  {
1448  int to = jter->first;
1449  allLinks.insert(std::make_pair(from, Link(from, to, Link::kUserClosure, poses.at(from).inverse()*poses.at(to))));
1450  }
1451  }
1452 
1453  _compensator->feed(clouds, allLinks);
1454  }
1455  else
1456  {
1457  _compensator->feed(clouds, links);
1458  }
1459 
1460  if(!(_ui->checkBox_meshing->isChecked() &&
1461  _ui->checkBox_textureMapping->isEnabled() &&
1462  _ui->checkBox_textureMapping->isChecked()))
1463  {
1464  _progressDialog->appendText(tr("Applying gain compensation..."));
1465  for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator jter=clouds.begin();jter!=clouds.end(); ++jter)
1466  {
1467  if(jter!=clouds.end())
1468  {
1469  double gain = _compensator->getGain(jter->first);;
1470  _compensator->apply(jter->first, jter->second.first, jter->second.second, _ui->checkBox_gainRGB->isChecked());
1471 
1472  _progressDialog->appendText(tr("Cloud %1 has gain %2").arg(jter->first).arg(gain));
1474  QApplication::processEvents();
1475  if(_canceled)
1476  {
1477  return false;
1478  }
1479  }
1480  }
1481  }
1482  }
1483 
1484  UDEBUG("");
1485  std::map<int, Transform> normalViewpoints = poses;
1486  if(_ui->checkBox_assemble->isChecked())
1487  {
1488  // Adjust view points with local transforms
1489  for(std::map<int, Transform>::iterator iter= normalViewpoints.begin(); iter!=normalViewpoints.end(); ++iter)
1490  {
1491  if(_ui->checkBox_fromDepth->isChecked())
1492  {
1493  std::vector<CameraModel> models;
1494  StereoCameraModel stereoModel;
1495  if(cachedSignatures.contains(iter->first))
1496  {
1497  const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
1498  models = data.cameraModels();
1499  stereoModel = data.stereoCameraModel();
1500  }
1501  else if(_dbDriver)
1502  {
1503  _dbDriver->getCalibration(iter->first, models, stereoModel);
1504  }
1505 
1506  if(models.size() && !models[0].localTransform().isNull())
1507  {
1508  iter->second *= models[0].localTransform();
1509  }
1510  else if(!stereoModel.localTransform().isNull())
1511  {
1512  iter->second *= stereoModel.localTransform();
1513  }
1514  }
1515  else
1516  {
1517  if(uContains(cachedScans, iter->first))
1518  {
1519  iter->second *= cachedScans.at(iter->first).localTransform();
1520  }
1521  else if(cachedSignatures.contains(iter->first))
1522  {
1523  const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
1524  if(!data.laserScanCompressed().isEmpty())
1525  {
1526  iter->second *= data.laserScanCompressed().localTransform();
1527  }
1528  else if(!data.laserScanRaw().isEmpty())
1529  {
1530  iter->second *= data.laserScanRaw().localTransform();
1531  }
1532  }
1533  else if(_dbDriver)
1534  {
1535  LaserScan scan;
1536  _dbDriver->getLaserScanInfo(iter->first, scan);
1537  iter->second *= scan.localTransform();
1538  }
1539  }
1540  }
1541  }
1542 
1543  UDEBUG("");
1544  pcl::PointCloud<pcl::PointXYZ>::Ptr rawAssembledCloud(new pcl::PointCloud<pcl::PointXYZ>);
1545  std::vector<int> rawCameraIndices;
1546  if(_ui->checkBox_assemble->isChecked() &&
1547  !((_ui->comboBox_pipeline->currentIndex()==0 || _ui->comboBox_meshingApproach->currentIndex()==4) && _ui->checkBox_meshing->isChecked()))
1548  {
1549  _progressDialog->appendText(tr("Assembling %1 clouds...").arg(clouds.size()));
1550  QApplication::processEvents();
1551 
1552  int i =0;
1553  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr assembledCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1554  for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator iter=clouds.begin();
1555  iter!= clouds.end();
1556  ++iter)
1557  {
1558  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformed(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1559  if(iter->second.first->isOrganized())
1560  {
1561  pcl::copyPointCloud(*iter->second.first, *iter->second.second, *transformed);
1562  transformed = util3d::transformPointCloud(transformed, poses.at(iter->first));
1563  }
1564  else
1565  {
1566  // it looks like that using only transformPointCloud with indices
1567  // flushes the colors, so we should extract points before... maybe a too old PCL version
1568  pcl::copyPointCloud(*iter->second.first, *iter->second.second, *transformed);
1569  transformed = rtabmap::util3d::transformPointCloud(transformed, poses.at(iter->first));
1570  }
1571 
1572  *assembledCloud += *transformed;
1573  rawCameraIndices.resize(assembledCloud->size(), iter->first);
1574 
1575  _progressDialog->appendText(tr("Assembled cloud %1, total=%2 (%3/%4).").arg(iter->first).arg(assembledCloud->size()).arg(++i).arg(clouds.size()));
1577  QApplication::processEvents();
1578  if(_canceled)
1579  {
1580  return false;
1581  }
1582  }
1583 
1584  assembledCloud->is_dense = true;
1585  pcl::copyPointCloud(*assembledCloud, *rawAssembledCloud);
1586 
1587  if(_ui->doubleSpinBox_voxelSize_assembled->value())
1588  {
1589  _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...")
1590  .arg(assembledCloud->size())
1591  .arg(_ui->doubleSpinBox_voxelSize_assembled->value()));
1592  QApplication::processEvents();
1593  unsigned int before = assembledCloud->size();
1594  assembledCloud = util3d::voxelize(
1595  assembledCloud,
1596  _ui->doubleSpinBox_voxelSize_assembled->value());
1597  _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...done! (%3 points)")
1598  .arg(before)
1599  .arg(_ui->doubleSpinBox_voxelSize_assembled->value())
1600  .arg(assembledCloud->size()));
1601  }
1602 
1603  clouds.clear();
1604  pcl::IndicesPtr indices(new std::vector<int>);
1605  indices->resize(assembledCloud->size());
1606  for(unsigned int i=0; i<indices->size(); ++i)
1607  {
1608  indices->at(i) = i;
1609  }
1610 
1611  if(!_ui->checkBox_fromDepth->isChecked() && !has2dScans)
1612  {
1613  // recompute normals
1614  pcl::PointCloud<pcl::PointXYZ>::Ptr cloudWithoutNormals(new pcl::PointCloud<pcl::PointXYZ>);
1615  pcl::copyPointCloud(*assembledCloud, *cloudWithoutNormals);
1616  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value());
1617 
1618  UASSERT(assembledCloud->size() == normals->size());
1619  for(unsigned int i=0; i<normals->size(); ++i)
1620  {
1621  assembledCloud->points[i].normal_x = normals->points[i].normal_x;
1622  assembledCloud->points[i].normal_y = normals->points[i].normal_y;
1623  assembledCloud->points[i].normal_z = normals->points[i].normal_z;
1624  }
1625 
1626  // adjust with point of views
1628  normalViewpoints,
1629  rawAssembledCloud,
1630  rawCameraIndices,
1631  assembledCloud);
1632  }
1633 
1634  clouds.insert(std::make_pair(0, std::make_pair(assembledCloud, indices)));
1635  }
1636 
1637  UDEBUG("");
1638  if(_canceled)
1639  {
1640  return false;
1641  }
1642 
1643  if(_ui->checkBox_smoothing->isEnabled() && _ui->checkBox_smoothing->isChecked() && !has2dScans)
1644  {
1645  _progressDialog->appendText(tr("Smoothing the surface using Moving Least Squares (MLS) algorithm... "
1646  "[search radius=%1m voxel=%2m]").arg(_ui->doubleSpinBox_mlsRadius->value()).arg(_ui->doubleSpinBox_voxelSize_assembled->value()));
1647  QApplication::processEvents();
1648  uSleep(100);
1649  QApplication::processEvents();
1650  }
1651 
1652  //fill cloudWithNormals
1653  for(std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator iter=clouds.begin();
1654  iter!= clouds.end();)
1655  {
1656  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudWithNormals = iter->second.first;
1657 
1658  if(_ui->checkBox_smoothing->isEnabled() && _ui->checkBox_smoothing->isChecked() && !has2dScans)
1659  {
1660  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals(new pcl::PointCloud<pcl::PointXYZRGB>);
1661  if(iter->second.second->size())
1662  {
1663  pcl::copyPointCloud(*cloudWithNormals, *iter->second.second, *cloudWithoutNormals);
1664  }
1665  else
1666  {
1667  pcl::copyPointCloud(*cloudWithNormals, *cloudWithoutNormals);
1668  }
1669 
1670  _progressDialog->appendText(tr("Smoothing (MLS) the cloud (%1 points)...").arg(cloudWithNormals->size()));
1671  QApplication::processEvents();
1672  uSleep(100);
1673  QApplication::processEvents();
1674  if(_canceled)
1675  {
1676  return false;
1677  }
1678 
1679  cloudWithNormals = util3d::mls(
1680  cloudWithoutNormals,
1681  (float)_ui->doubleSpinBox_mlsRadius->value(),
1682  _ui->spinBox_polygonialOrder->value(),
1683  _ui->comboBox_upsamplingMethod->currentIndex(),
1684  (float)_ui->doubleSpinBox_sampleRadius->value(),
1685  (float)_ui->doubleSpinBox_sampleStep->value(),
1686  _ui->spinBox_randomPoints->value(),
1687  (float)_ui->doubleSpinBox_dilationVoxelSize->value(),
1688  _ui->spinBox_dilationSteps->value());
1689 
1690  // make sure there are no nans
1691  UDEBUG("NaNs filtering... size before = %d", cloudWithNormals->size());
1692  cloudWithNormals = util3d::removeNaNNormalsFromPointCloud(cloudWithNormals);
1693  UDEBUG("NaNs filtering... size after = %d", cloudWithNormals->size());
1694 
1695  if(_ui->checkBox_assemble->isChecked())
1696  {
1697  // Re-voxelize to make sure to have uniform density
1698  if(_ui->doubleSpinBox_mls_outputVoxelSize->value())
1699  {
1700  _progressDialog->appendText(tr("Voxelize cloud (%1 points, voxel size = %2 m)...")
1701  .arg(cloudWithNormals->size())
1702  .arg(_ui->doubleSpinBox_mls_outputVoxelSize->value()));
1703  QApplication::processEvents();
1704 
1705  cloudWithNormals = util3d::voxelize(
1706  cloudWithNormals,
1707  _ui->doubleSpinBox_mls_outputVoxelSize->value());
1708  }
1709 
1710  _progressDialog->appendText(tr("Update %1 normals with %2 camera views...").arg(cloudWithNormals->size()).arg(poses.size()));
1711 
1713  normalViewpoints,
1714  rawAssembledCloud,
1715  rawCameraIndices,
1716  cloudWithNormals);
1717  }
1718  }
1719  else if(iter->second.first->isOrganized() && _ui->checkBox_filtering->isChecked())
1720  {
1721  cloudWithNormals = util3d::extractIndices(iter->second.first, iter->second.second, false, true);
1722  }
1723 
1724  cloudsWithNormals.insert(std::make_pair(iter->first, cloudWithNormals));
1725 
1726  // clear memory
1727  clouds.erase(iter++);
1728 
1730  QApplication::processEvents();
1731  if(_canceled)
1732  {
1733  return false;
1734  }
1735  }
1736 
1737  UDEBUG("");
1738 #ifdef RTABMAP_CPUTSDF
1739  cpu_tsdf::TSDFVolumeOctree::Ptr tsdf;
1740 #endif
1741 #ifdef RTABMAP_OPENCHISEL
1742  chisel::ChiselPtr chiselMap;
1743  chisel::ProjectionIntegrator projectionIntegrator;
1744 #endif
1745 
1746  //used for organized texturing below
1747  std::map<int, std::vector<int> > organizedIndices;
1748  std::map<int, cv::Size> organizedCloudSizes;
1749 
1750  //mesh
1751  UDEBUG("Meshing=%d", _ui->checkBox_meshing->isChecked()?1:0);
1752  if(_ui->checkBox_meshing->isChecked() && !has2dScans)
1753  {
1754 
1755 #ifdef RTABMAP_OPENCHISEL
1756  if(_ui->comboBox_meshingApproach->currentIndex()==4 && _ui->checkBox_assemble->isChecked())
1757  {
1758  _progressDialog->appendText(tr("Creating TSDF volume with OpenChisel... "));
1759 
1760  QApplication::processEvents();
1761  uSleep(100);
1762  QApplication::processEvents();
1763 
1764  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1765  std::vector<pcl::Vertices> mergedPolygons;
1766 
1767  int cloudsAdded = 1;
1768  for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::iterator iter=cloudsWithNormals.begin();
1769  iter!= cloudsWithNormals.end();
1770  ++iter,++cloudsAdded)
1771  {
1772  std::vector<CameraModel> models;
1773  StereoCameraModel stereoModel;
1774  bool cacheHasCompressedImage = false;
1775  LaserScan scanInfo;
1776  if(cachedSignatures.contains(iter->first))
1777  {
1778  const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
1779  models = data.cameraModels();
1780  cacheHasCompressedImage = !data.imageCompressed().empty();
1781  scanInfo = !data.laserScanRaw().isEmpty()?data.laserScanRaw():data.laserScanCompressed();
1782  }
1783  else if(_dbDriver)
1784  {
1785  _dbDriver->getCalibration(iter->first, models, stereoModel);
1786  _dbDriver->getLaserScanInfo(iter->first, scanInfo);
1787  }
1788 
1789  if(chiselMap.get() == 0)
1790  {
1791  UDEBUG("");
1792  int chunkSizeX = _ui->spinBox_openchisel_chunk_size_x->value();
1793  int chunkSizeY = _ui->spinBox_openchisel_chunk_size_y->value();
1794  int chunkSizeZ = _ui->spinBox_openchisel_chunk_size_z->value();
1795  float voxelResolution = _ui->doubleSpinBox_voxelSize_assembled->value();
1796  if(voxelResolution <=0.0f)
1797  {
1798  _progressDialog->appendText(tr("OpenChisel: Voxel size should not be null!"), Qt::darkYellow);
1799  _progressDialog->setAutoClose(false);
1800  break;
1801  }
1802  bool useColor = _ui->checkBox_fromDepth->isChecked();
1803  chiselMap.reset(new chisel::Chisel(Eigen::Vector3i(chunkSizeX, chunkSizeY, chunkSizeZ), voxelResolution, useColor));
1804  double truncationDistConst = _ui->doubleSpinBox_openchisel_truncation_constant->value();
1805  double truncationDistLinear = _ui->doubleSpinBox_openchisel_truncation_linear->value();
1806  double truncationDistQuad = _ui->doubleSpinBox_openchisel_truncation_quadratic->value();
1807  double truncationDistScale = _ui->doubleSpinBox_openchisel_truncation_scale->value();
1808  int weight = _ui->spinBox_openchisel_integration_weight->value();
1809  bool useCarving = _ui->checkBox_openchisel_use_voxel_carving->isChecked();
1810  double carvingDist = _ui->doubleSpinBox_openchisel_carving_dist_m->value();
1811  chisel::Vec4 truncation(truncationDistQuad, truncationDistLinear, truncationDistConst, truncationDistScale);
1812  UDEBUG("If crashing just after this message, make sure PCL and OpenChisel are built both with -march=native or both without -march=native");
1813  projectionIntegrator.SetCentroids(chiselMap->GetChunkManager().GetCentroids());
1814  projectionIntegrator.SetTruncator(chisel::TruncatorPtr(new chisel::QuadraticTruncator(truncation(0), truncation(1), truncation(2), truncation(3))));
1815  projectionIntegrator.SetWeighter(chisel::WeighterPtr(new chisel::ConstantWeighter(weight)));
1816  projectionIntegrator.SetCarvingDist(carvingDist);
1817  projectionIntegrator.SetCarvingEnabled(useCarving);
1818  }
1819 
1820  UDEBUG("");
1821  double nearPlaneDist = _ui->doubleSpinBox_openchisel_near_plane_dist->value();
1822  double farPlaneDist = _ui->doubleSpinBox_openchisel_far_plane_dist->value();
1823  if(_ui->checkBox_fromDepth->isChecked())
1824  {
1825  if(models.size() == 1 && !models[0].localTransform().isNull())
1826  {
1827  // get just the depth
1828  cv::Mat rgb;
1829  cv::Mat depth;
1830  if(cacheHasCompressedImage)
1831  {
1832  cachedSignatures.find(iter->first)->sensorData().uncompressDataConst(&rgb, &depth);
1833  }
1834  else if(_dbDriver)
1835  {
1836  SensorData data;
1837  _dbDriver->getNodeData(iter->first, data, true, false, false, false);
1838  data.uncompressDataConst(&rgb, &depth);
1839  }
1840  if(!rgb.empty() && !depth.empty())
1841  {
1842  CameraModel rgbModel = models[0];
1843  CameraModel depthModel = rgbModel;
1844  if(rgb.cols > depth.cols)
1845  {
1846  UASSERT(rgb.cols % depth.cols == 0);
1847  depthModel = depthModel.scaled(double(depth.cols)/double(rgb.cols));
1848  }
1849 
1850  if(depth.type() == CV_16UC1)
1851  {
1852  depth = util2d::cvtDepthToFloat(depth);
1853  }
1854 
1855  std::shared_ptr<chisel::ColorImage<unsigned char> > colorChisel = colorImageToChisel(rgb);
1856  std::shared_ptr<chisel::DepthImage<float> > depthChisel = depthImageToChisel(depth);
1857 
1858  chisel::PinholeCamera cameraColor = cameraModelToChiselCamera(rgbModel);
1859  chisel::PinholeCamera cameraDepth = cameraModelToChiselCamera(depthModel);
1860  cameraColor.SetNearPlane(nearPlaneDist);
1861  cameraColor.SetFarPlane(farPlaneDist);
1862  cameraDepth.SetNearPlane(nearPlaneDist);
1863  cameraDepth.SetFarPlane(farPlaneDist);
1864 
1865  chisel::Transform pose_rel_to_first_frame = (poses.at(iter->first)*models[0].localTransform()).toEigen3f();
1866  chiselMap->IntegrateDepthScanColor<float, unsigned char>(projectionIntegrator, depthChisel, pose_rel_to_first_frame, cameraDepth, colorChisel, pose_rel_to_first_frame, cameraColor);
1867  UDEBUG("");
1868  }
1869  else
1870  {
1871  _progressDialog->appendText(tr("OpenChisel: Depth and RGB images not found for %1!").arg(iter->first), Qt::darkYellow);
1872  }
1873  }
1874  else
1875  {
1876  _progressDialog->appendText(tr("OpenChisel: Invalid camera model for cloud %1! Only single RGB-D camera supported.").arg(iter->first), Qt::darkYellow);
1877  _progressDialog->setAutoClose(false);
1878  break;
1879  }
1880  }
1881  else if(!scanInfo.localTransform().isNull())
1882  {
1883  chisel::PointCloudPtr chiselCloud = pointCloudRGBToChisel(*iter->second, scanInfo.localTransform().inverse());
1884  chisel::Transform pose_rel_to_first_frame = (poses.at(iter->first)*scanInfo.localTransform()).toEigen3f();
1885  chiselMap->IntegratePointCloud(projectionIntegrator, *chiselCloud, pose_rel_to_first_frame, farPlaneDist);
1886  UDEBUG("");
1887  }
1888  else
1889  {
1890  _progressDialog->appendText(tr("OpenChisel: not valid scan info for cloud %1!").arg(iter->first), Qt::darkYellow);
1891  _progressDialog->setAutoClose(false);
1892  break;
1893  }
1894  chiselMap->UpdateMeshes();
1895  UDEBUG("");
1896  _progressDialog->appendText(tr("OpenChisel: Integrated cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
1897 
1899  QApplication::processEvents();
1900  if(_canceled)
1901  {
1902  return false;
1903  }
1904  }
1905  }
1906  else
1907 #endif
1908 
1909  if(_ui->comboBox_pipeline->currentIndex() == 0)
1910  {
1911  if(_ui->comboBox_meshingApproach->currentIndex()==2)
1912  {
1913  _progressDialog->appendText(tr("Creating TSDF volume with CPUTSDF... "));
1914  }
1915  else
1916  {
1917  _progressDialog->appendText(tr("Organized fast mesh... "));
1918  }
1919  QApplication::processEvents();
1920  uSleep(100);
1921  QApplication::processEvents();
1922 
1923  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1924  std::vector<pcl::Vertices> mergedPolygons;
1925 
1926  int cloudsAdded = 1;
1927  for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::iterator iter=cloudsWithNormals.begin();
1928  iter!= cloudsWithNormals.end();
1929  ++iter,++cloudsAdded)
1930  {
1931  if(iter->second->isOrganized())
1932  {
1933  if(iter->second->size())
1934  {
1935  Eigen::Vector3f viewpoint(0.0f,0.0f,0.0f);
1936 
1937  std::vector<CameraModel> models;
1938  StereoCameraModel stereoModel;
1939  if(cachedSignatures.contains(iter->first))
1940  {
1941  const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
1942  models = data.cameraModels();
1943  stereoModel = data.stereoCameraModel();
1944  }
1945  else if(_dbDriver)
1946  {
1947  _dbDriver->getCalibration(iter->first, models, stereoModel);
1948  }
1949 
1950 #ifdef RTABMAP_CPUTSDF
1951  if(_ui->comboBox_meshingApproach->currentIndex()==2 && _ui->checkBox_assemble->isChecked())
1952  {
1953  if(tsdf.get() == 0)
1954  {
1955  if(models.size()==1 && models[0].isValidForProjection() && models[0].imageHeight()>0 && models[0].imageWidth()>0)
1956  {
1957  float tsdf_size = _ui->doubleSpinBox_cputsdf_size->value();
1958  float cell_size = _ui->doubleSpinBox_cputsdf_resolution->value();
1959  int num_random_splits = _ui->spinBox_cputsdf_randomSplit->value();
1960  int tsdf_res;
1961  int desired_res = tsdf_size / cell_size;
1962  // Snap to nearest power of 2;
1963  int n = 1;
1964  while (desired_res > n)
1965  {
1966  n *= 2;
1967  }
1968  tsdf_res = n;
1969  _progressDialog->appendText(tr("CPU-TSDF: Setting resolution: %1 with grid size %2").arg(tsdf_res).arg(tsdf_size));
1970  tsdf.reset (new cpu_tsdf::TSDFVolumeOctree);
1971  tsdf->setGridSize (tsdf_size, tsdf_size, tsdf_size);
1972  tsdf->setResolution (tsdf_res, tsdf_res, tsdf_res);
1973  float decimation = float(models[0].imageWidth()) / float(iter->second->width);
1974  tsdf->setImageSize (models[0].imageWidth()/decimation, models[0].imageHeight()/decimation);
1975  tsdf->setCameraIntrinsics (models[0].fx()/decimation, models[0].fy()/decimation, models[0].cx()/decimation, models[0].cy()/decimation);
1976  tsdf->setNumRandomSplts (num_random_splits);
1977  tsdf->setSensorDistanceBounds (0, 9999);
1978  tsdf->setIntegrateColor(true);
1979  tsdf->setDepthTruncationLimits (_ui->doubleSpinBox_cputsdf_tuncPos->value(), _ui->doubleSpinBox_cputsdf_tuncNeg->value());
1980  tsdf->reset ();
1981  }
1982  else
1983  {
1984  _progressDialog->appendText(tr("CPU-TSDF: Invalid camera model! Only single RGB-D camera supported."), Qt::darkYellow);
1985  _progressDialog->setAutoClose(false);
1986  break;
1987  }
1988  }
1989 
1990  if(tsdf.get())
1991  {
1992  if(tsdf.get() && models.size() == 1 && !models[0].localTransform().isNull())
1993  {
1994  Eigen::Affine3d pose_rel_to_first_frame = ((poses.begin()->second.inverse() * poses.at(iter->first))*models[0].localTransform()).toEigen3d();
1995  if(!tsdf->integrateCloud(*util3d::transformPointCloud(iter->second, models[0].localTransform().inverse()), pcl::PointCloud<pcl::Normal>(), pose_rel_to_first_frame))
1996  {
1997  _progressDialog->appendText(tr("CPU-TSDF: Failed integrating cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
1998  }
1999  else
2000  {
2001  _progressDialog->appendText(tr("CPU-TSDF: Integrated cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2002  }
2003  }
2004  }
2005  }
2006  else
2007 #endif
2008  {
2009  if((_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex() != 2) ||
2010  !iter->second->isOrganized())
2011  {
2012  if(models.size() && !models[0].localTransform().isNull())
2013  {
2014  viewpoint[0] = models[0].localTransform().x();
2015  viewpoint[1] = models[0].localTransform().y();
2016  viewpoint[2] = models[0].localTransform().z();
2017  }
2018  else if(!stereoModel.localTransform().isNull())
2019  {
2020  viewpoint[0] = stereoModel.localTransform().x();
2021  viewpoint[1] = stereoModel.localTransform().y();
2022  viewpoint[2] = stereoModel.localTransform().z();
2023  }
2024  }
2025 
2026  std::vector<pcl::Vertices> polygons = util3d::organizedFastMesh(
2027  iter->second,
2028  _ui->doubleSpinBox_mesh_angleTolerance->value()*M_PI/180.0,
2029  _ui->checkBox_mesh_quad->isEnabled() && _ui->checkBox_mesh_quad->isChecked(),
2030  _ui->spinBox_mesh_triangleSize->value(),
2031  viewpoint);
2032 
2033  if(_ui->spinBox_mesh_minClusterSize->value() != 0)
2034  {
2035  _progressDialog->appendText(tr("Filter small polygon clusters..."));
2036  QApplication::processEvents();
2037 
2038  // filter polygons
2039  std::vector<std::set<int> > neighbors;
2040  std::vector<std::set<int> > vertexToPolygons;
2042  (int)iter->second->size(),
2043  neighbors,
2044  vertexToPolygons);
2045  std::list<std::list<int> > clusters = util3d::clusterPolygons(
2046  neighbors,
2047  _ui->spinBox_mesh_minClusterSize->value()<0?0:_ui->spinBox_mesh_minClusterSize->value());
2048 
2049  std::vector<pcl::Vertices> filteredPolygons(polygons.size());
2050  if(_ui->spinBox_mesh_minClusterSize->value() < 0)
2051  {
2052  // only keep the biggest cluster
2053  std::list<std::list<int> >::iterator biggestClusterIndex = clusters.end();
2054  unsigned int biggestClusterSize = 0;
2055  for(std::list<std::list<int> >::iterator iter=clusters.begin(); iter!=clusters.end(); ++iter)
2056  {
2057  if(iter->size() > biggestClusterSize)
2058  {
2059  biggestClusterIndex = iter;
2060  biggestClusterSize = iter->size();
2061  }
2062  }
2063  if(biggestClusterIndex != clusters.end())
2064  {
2065  int oi=0;
2066  for(std::list<int>::iterator jter=biggestClusterIndex->begin(); jter!=biggestClusterIndex->end(); ++jter)
2067  {
2068  filteredPolygons[oi++] = polygons.at(*jter);
2069  }
2070  filteredPolygons.resize(oi);
2071  }
2072  }
2073  else
2074  {
2075  int oi=0;
2076  for(std::list<std::list<int> >::iterator iter=clusters.begin(); iter!=clusters.end(); ++iter)
2077  {
2078  for(std::list<int>::iterator jter=iter->begin(); jter!=iter->end(); ++jter)
2079  {
2080  filteredPolygons[oi++] = polygons.at(*jter);
2081  }
2082  }
2083  filteredPolygons.resize(oi);
2084  }
2085  int before = (int)polygons.size();
2086  polygons = filteredPolygons;
2087 
2088  if(polygons.size() == 0)
2089  {
2090  std::string msg = uFormat("All %d polygons filtered after polygon cluster filtering. Cluster minimum size is %d.", before, _ui->spinBox_mesh_minClusterSize->value());
2091  _progressDialog->appendText(msg.c_str(), Qt::darkYellow);
2092  UWARN(msg.c_str());
2093  }
2094 
2095  _progressDialog->appendText(tr("Filtered %1 polygons.").arg(before-(int)polygons.size()));
2096  QApplication::processEvents();
2097  }
2098 
2099  _progressDialog->appendText(tr("Mesh %1 created with %2 polygons (%3/%4).").arg(iter->first).arg(polygons.size()).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2100 
2101  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr denseCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2102  std::vector<pcl::Vertices> densePolygons;
2103  std::vector<int> denseToOrganizedIndices = util3d::filterNotUsedVerticesFromMesh(*iter->second, polygons, *denseCloud, densePolygons);
2104 
2105  if(!_ui->checkBox_assemble->isChecked() ||
2106  (_ui->checkBox_textureMapping->isEnabled() &&
2107  _ui->checkBox_textureMapping->isChecked() &&
2108  _ui->doubleSpinBox_voxelSize_assembled->value() == 0.0)) // don't assemble now if we are texturing
2109  {
2110  if(_ui->checkBox_assemble->isChecked())
2111  {
2112  denseCloud = util3d::transformPointCloud(denseCloud, poses.at(iter->first));
2113  }
2114 
2115  pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
2116  pcl::toPCLPointCloud2(*denseCloud, mesh->cloud);
2117  mesh->polygons = densePolygons;
2118 
2119  organizedIndices.insert(std::make_pair(iter->first, denseToOrganizedIndices));
2120  organizedCloudSizes.insert(std::make_pair(iter->first, cv::Size(iter->second->width, iter->second->height)));
2121 
2122  meshes.insert(std::make_pair(iter->first, mesh));
2123  }
2124  else
2125  {
2126  denseCloud = util3d::transformPointCloud(denseCloud, poses.at(iter->first));
2127  if(mergedClouds->size() == 0)
2128  {
2129  *mergedClouds = *denseCloud;
2130  mergedPolygons = densePolygons;
2131  }
2132  else
2133  {
2134  util3d::appendMesh(*mergedClouds, mergedPolygons, *denseCloud, densePolygons);
2135  }
2136  }
2137  }
2138  }
2139  else
2140  {
2141  _progressDialog->appendText(tr("Mesh %1 not created (no valid points) (%2/%3).").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2142  }
2143  }
2144  else
2145  {
2146  int weight = 0;
2147  if(cachedSignatures.contains(iter->first))
2148  {
2149  const Signature & s = cachedSignatures.find(iter->first).value();
2150  weight = s.getWeight();
2151  }
2152  else if(_dbDriver)
2153  {
2154  _dbDriver->getWeight(iter->first, weight);
2155  }
2156  if(weight>=0) // don't show error for intermediate nodes
2157  {
2158  _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()));
2159  }
2160  }
2161 
2163  QApplication::processEvents();
2164  if(_canceled)
2165  {
2166  return false;
2167  }
2168  }
2169 
2170  if(_ui->checkBox_assemble->isChecked() && mergedClouds->size())
2171  {
2172  if(_ui->doubleSpinBox_voxelSize_assembled->value())
2173  {
2174  _progressDialog->appendText(tr("Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").arg(mergedClouds->size()).arg(mergedPolygons.size()));
2175  QApplication::processEvents();
2176 
2177  mergedPolygons = util3d::filterCloseVerticesFromMesh(
2178  mergedClouds,
2179  mergedPolygons,
2180  _ui->doubleSpinBox_voxelSize_assembled->value(),
2181  M_PI/4,
2182  true);
2183 
2184  // filter invalid polygons
2185  unsigned int count = mergedPolygons.size();
2186  mergedPolygons = util3d::filterInvalidPolygons(mergedPolygons);
2187  _progressDialog->appendText(tr("Filtered %1 invalid polygons.").arg(count-mergedPolygons.size()));
2188  QApplication::processEvents();
2189 
2190  // filter not used vertices
2191  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2192  std::vector<pcl::Vertices> filteredPolygons;
2193  util3d::filterNotUsedVerticesFromMesh(*mergedClouds, mergedPolygons, *filteredCloud, filteredPolygons);
2194  mergedClouds = filteredCloud;
2195  mergedPolygons = filteredPolygons;
2196  }
2197 
2198  pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
2199  pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
2200  mesh->polygons = mergedPolygons;
2201 
2202  meshes.insert(std::make_pair(0, mesh));
2203 
2205  QApplication::processEvents();
2206  }
2207  }
2208  else // dense pipeline
2209  {
2210  if(_ui->comboBox_meshingApproach->currentIndex() == 0)
2211  {
2212  _progressDialog->appendText(tr("Greedy projection triangulation... [radius=%1m]").arg(_ui->doubleSpinBox_gp3Radius->value()));
2213  }
2214  else
2215  {
2216  _progressDialog->appendText(tr("Poisson surface reconstruction..."));
2217  }
2218  QApplication::processEvents();
2219  uSleep(100);
2220  QApplication::processEvents();
2221 
2222  int cloudsAdded=1;
2223  for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::iterator iter=cloudsWithNormals.begin();
2224  iter!= cloudsWithNormals.end();
2225  ++iter,++cloudsAdded)
2226  {
2227  pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
2228  if(_ui->comboBox_meshingApproach->currentIndex() == 0)
2229  {
2230  mesh = util3d::createMesh(
2231  iter->second,
2232  _ui->doubleSpinBox_gp3Radius->value(),
2233  _ui->doubleSpinBox_gp3Mu->value());
2234  }
2235  else
2236  {
2237  pcl::Poisson<pcl::PointXYZRGBNormal> poisson;
2238  poisson.setOutputPolygons(_ui->checkBox_poisson_outputPolygons->isEnabled()?_ui->checkBox_poisson_outputPolygons->isChecked():false);
2239  poisson.setManifold(_ui->checkBox_poisson_manifold->isChecked());
2240  poisson.setSamplesPerNode(_ui->doubleSpinBox_poisson_samples->value());
2241  int depth = _ui->spinBox_poisson_depth->value();
2242  if(depth == 0)
2243  {
2244  Eigen::Vector4f min,max;
2245  pcl::getMinMax3D(*iter->second, min, max);
2246  float mapLength = uMax3(max[0]-min[0], max[1]-min[1], max[2]-min[2]);
2247  depth = 12;
2248  for(int i=6; i<12; ++i)
2249  {
2250  if(mapLength/float(1<<i) < 0.03f)
2251  {
2252  depth = i;
2253  break;
2254  }
2255  }
2256  _progressDialog->appendText(tr("Poisson depth resolution chosen is %1, map size (m) = %2x%3x%4")
2257  .arg(depth)
2258  .arg(int(max[0]-min[0]))
2259  .arg(int(max[1]-min[1]))
2260  .arg(int(max[2]-min[2])));
2261  QApplication::processEvents();
2262  uSleep(100);
2263  QApplication::processEvents();
2264  }
2265  poisson.setDepth(depth);
2266  poisson.setIsoDivide(_ui->spinBox_poisson_iso->value());
2267  poisson.setSolverDivide(_ui->spinBox_poisson_solver->value());
2268  poisson.setMinDepth(_ui->spinBox_poisson_minDepth->value());
2269  poisson.setPointWeight(_ui->doubleSpinBox_poisson_pointWeight->value());
2270  poisson.setScale(_ui->doubleSpinBox_poisson_scale->value());
2271  poisson.setInputCloud(iter->second);
2272  poisson.reconstruct(*mesh);
2273  }
2274 
2275  _progressDialog->appendText(tr("Mesh %1 created with %2 polygons (%3/%4).").arg(iter->first).arg(mesh->polygons.size()).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2276  QApplication::processEvents();
2277 
2278  if(mesh->polygons.size()>0)
2279  {
2280  TexturingState texturingState(_progressDialog, false);
2281  util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
2282  mesh,
2283  _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
2284  _ui->spinBox_meshMaxPolygons->isEnabled()?_ui->spinBox_meshMaxPolygons->value():0,
2285  iter->second,
2286  (float)_ui->doubleSpinBox_transferColorRadius->value(),
2287  !(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()),
2288  _ui->checkBox_cleanMesh->isChecked(),
2289  _ui->spinBox_mesh_minClusterSize->value(),
2290  &texturingState);
2291  meshes.insert(std::make_pair(iter->first, mesh));
2292  }
2293  else
2294  {
2295  _progressDialog->appendText(tr("No polygons created for cloud %d!").arg(iter->first), Qt::darkYellow);
2296  _progressDialog->setAutoClose(false);
2297  }
2298 
2299  _progressDialog->incrementStep(_ui->checkBox_assemble->isChecked()?poses.size():1);
2300  QApplication::processEvents();
2301  if(_canceled)
2302  {
2303  return false;
2304  }
2305  }
2306  }
2307  }
2308  else if(_ui->checkBox_meshing->isChecked())
2309  {
2310  std::string msg = uFormat("Some clouds are 2D laser scans. Meshing can be done only from RGB-D clouds or 3D laser scans.");
2311  _progressDialog->appendText(msg.c_str(), Qt::darkYellow);
2312  UWARN(msg.c_str());
2313  }
2314 
2315  UDEBUG("");
2316 #ifdef RTABMAP_CPUTSDF
2317  if(tsdf.get())
2318  {
2319  _progressDialog->appendText(tr("CPU-TSDF: Creating mesh from TSDF volume..."));
2320  QApplication::processEvents();
2321  uSleep(100);
2322  QApplication::processEvents();
2323 
2324  cpu_tsdf::MarchingCubesTSDFOctree mc;
2325  mc.setMinWeight (_ui->doubleSpinBox_cputsdf_minWeight->value());
2326  mc.setInputTSDF (tsdf);
2327  mc.setColorByRGB (true);
2328  pcl::PolygonMesh::Ptr mesh (new pcl::PolygonMesh);
2329  mc.reconstruct (*mesh);
2330  _progressDialog->appendText(tr("CPU-TSDF: Creating mesh from TSDF volume...done! %1 polygons").arg(mesh->polygons.size()));
2331  meshes.clear();
2332 
2333  if(mesh->polygons.size()>0)
2334  {
2335 
2336  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr vertices (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2337  pcl::fromPCLPointCloud2 (mesh->cloud, *vertices);
2338 
2339  if(_ui->doubleSpinBox_cputsdf_flattenRadius->value()>0.0)
2340  {
2341  _progressDialog->appendText(tr("CPU-TSDF: Flattening mesh (radius=%1)...").arg(_ui->doubleSpinBox_cputsdf_flattenRadius->value()));
2342  QApplication::processEvents();
2343  uSleep(100);
2344  QApplication::processEvents();
2345 
2346  float min_dist = _ui->doubleSpinBox_cputsdf_flattenRadius->value();
2347  pcl::search::KdTree<pcl::PointXYZRGBNormal> vert_tree (true);
2348  vert_tree.setInputCloud (vertices);
2349  // Find duplicates
2350  std::vector<int> vertex_remap (vertices->size (), -1);
2351  int idx = 0;
2352  std::vector<int> neighbors;
2353  std::vector<float> dists;
2354  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr vertices_new(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2355  vertices_new->resize(vertices->size ());
2356  for (size_t i = 0; i < vertices->size (); i++)
2357  {
2358  if (vertex_remap[i] >= 0)
2359  continue;
2360  vertex_remap[i] = idx;
2361  vert_tree.radiusSearch (i, min_dist, neighbors, dists);
2362  for (size_t j = 1; j < neighbors.size (); j++)
2363  {
2364  if (dists[j] < min_dist)
2365  vertex_remap[neighbors[j]] = idx;
2366  }
2367  vertices_new->at(idx++) = vertices->at (i);
2368  }
2369  vertices_new->resize(idx);
2370  std::vector<size_t> faces_to_remove;
2371  size_t face_idx = 0;
2372  for (size_t i = 0; i < mesh->polygons.size (); i++)
2373  {
2374  pcl::Vertices &v = mesh->polygons[i];
2375  for (size_t j = 0; j < v.vertices.size (); j++)
2376  {
2377  v.vertices[j] = vertex_remap[v.vertices[j]];
2378  }
2379  if (!(v.vertices[0] == v.vertices[1] || v.vertices[1] == v.vertices[2] || v.vertices[2] == v.vertices[0]))
2380  {
2381  mesh->polygons[face_idx++] = mesh->polygons[i];
2382  }
2383  }
2384  mesh->polygons.resize (face_idx);
2385  pcl::toPCLPointCloud2 (*vertices_new, mesh->cloud);
2386  vertices = vertices_new;
2387  }
2388 
2389  pcl::fromPCLPointCloud2(mesh->cloud, *vertices);
2390  TexturingState texturingState(_progressDialog, false);
2391  util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
2392  mesh,
2393  _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
2394  _ui->spinBox_meshMaxPolygons->isEnabled()?_ui->spinBox_meshMaxPolygons->value():0,
2395  vertices,
2396  (float)_ui->doubleSpinBox_transferColorRadius->value(),
2397  !(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()),
2398  _ui->checkBox_cleanMesh->isChecked(),
2399  _ui->spinBox_mesh_minClusterSize->value(),
2400  &texturingState);
2401  meshes.insert(std::make_pair(0, mesh));
2402  }
2403  else
2404  {
2405  _progressDialog->appendText(tr("No polygons created TSDF volume!"), Qt::darkYellow);
2406  _progressDialog->setAutoClose(false);
2407  }
2408  }
2409 #endif
2410 #ifdef RTABMAP_OPENCHISEL
2411  if(chiselMap.get())
2412  {
2413  _progressDialog->appendText(tr("OpenChisel: Creating mesh from TSDF volume..."));
2414  QApplication::processEvents();
2415  uSleep(100);
2416  QApplication::processEvents();
2417 
2418  const chisel::MeshMap& meshMap = chiselMap->GetChunkManager().GetAllMeshes();
2419  pcl::PolygonMesh::Ptr mesh = chiselToPolygonMesh(meshMap);
2420 
2421  // To debug...
2422  //std::string filePly = _workingDirectory.toStdString()+"/"+"chisel.ply";
2423  //chiselMap->SaveAllMeshesToPLY(filePly);
2424  //UWARN("Saved %s", filePly.c_str());
2425 
2426  _progressDialog->appendText(tr("OpenChisel: Creating mesh from TSDF volume...done! %1 polygons").arg(mesh->polygons.size()));
2427 
2428  meshes.clear();
2429  if(mesh->polygons.size()>0)
2430  {
2431  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2432  pcl::fromPCLPointCloud2(mesh->cloud, *mergedClouds);
2433  if(_ui->checkBox_openchisel_mergeVertices->isChecked())
2434  {
2435  _progressDialog->appendText(tr("Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").arg(mergedClouds->size()).arg(mesh->polygons.size()));
2436  QApplication::processEvents();
2437 
2438  mesh->polygons = util3d::filterCloseVerticesFromMesh(
2439  mergedClouds,
2440  mesh->polygons,
2441  _ui->doubleSpinBox_voxelSize_assembled->value()/2.0,
2442  M_PI/4,
2443  true);
2444 
2445  // filter invalid polygons
2446  unsigned int count = mesh->polygons.size();
2447  mesh->polygons = util3d::filterInvalidPolygons(mesh->polygons);
2448  _progressDialog->appendText(tr("Filtered %1 invalid polygons.").arg(count-mesh->polygons.size()));
2449  QApplication::processEvents();
2450 
2451  // filter not used vertices
2452  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2453  std::vector<pcl::Vertices> filteredPolygons;
2454  count = mergedClouds->size();
2455  util3d::filterNotUsedVerticesFromMesh(*mergedClouds, mesh->polygons, *filteredCloud, filteredPolygons);
2456  mergedClouds = filteredCloud;
2457  pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
2458  mesh->polygons = filteredPolygons;
2459  _progressDialog->appendText(tr("Filtered %1 duplicate vertices.").arg(count-mergedClouds->size()));
2460  QApplication::processEvents();
2461  }
2462  TexturingState texturingState(_progressDialog, false);
2463  util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
2464  mesh,
2465  _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
2466  _ui->spinBox_meshMaxPolygons->isEnabled()?_ui->spinBox_meshMaxPolygons->value():0,
2467  mergedClouds,
2468  (float)_ui->doubleSpinBox_transferColorRadius->value(),
2469  !(_ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()),
2470  _ui->checkBox_cleanMesh->isChecked(),
2471  _ui->spinBox_mesh_minClusterSize->value(),
2472  &texturingState);
2473  meshes.insert(std::make_pair(0, mesh));
2474  }
2475  else
2476  {
2477  _progressDialog->appendText(tr("No polygons created TSDF volume!"), Qt::darkYellow);
2478  _progressDialog->setAutoClose(false);
2479  }
2480  }
2481 #endif
2482 
2483  UDEBUG("");
2484  if(_canceled)
2485  {
2486  return false;
2487  }
2488 
2489  // texture mesh
2490  UDEBUG("texture mapping=%d", _ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked()?1:0);
2491  if(!has2dScans && _ui->checkBox_textureMapping->isEnabled() && _ui->checkBox_textureMapping->isChecked())
2492  {
2493  _progressDialog->appendText(tr("Texturing..."));
2494  QApplication::processEvents();
2495  uSleep(100);
2496  QApplication::processEvents();
2497 
2498  int i=0;
2499  for(std::map<int, pcl::PolygonMesh::Ptr>::iterator iter=meshes.begin();
2500  iter!= meshes.end();
2501  ++iter)
2502  {
2503  std::map<int, Transform> cameras;
2504  if(iter->first == 0)
2505  {
2506  cameras = poses;
2507  }
2508  else
2509  {
2510  UASSERT(uContains(poses, iter->first));
2511  cameras.insert(std::make_pair(iter->first, _ui->checkBox_assemble->isChecked()?poses.at(iter->first):Transform::getIdentity()));
2512  }
2513  std::map<int, Transform> cameraPoses;
2514  std::map<int, std::vector<CameraModel> > cameraModels;
2515  std::map<int, cv::Mat > cameraDepths;
2516  int ignoredCameras = 0;
2517  for(std::map<int, Transform>::iterator jter=cameras.begin(); jter!=cameras.end(); ++jter)
2518  {
2519  if(validCameras.find(jter->first) != validCameras.end())
2520  {
2521  std::vector<CameraModel> models;
2522  StereoCameraModel stereoModel;
2523  bool cacheHasCompressedImage = false;
2524  if(cachedSignatures.contains(jter->first))
2525  {
2526  const SensorData & data = cachedSignatures.find(jter->first)->sensorData();
2527  models = data.cameraModels();
2528  stereoModel = data.stereoCameraModel();
2529  cacheHasCompressedImage = !data.imageCompressed().empty();
2530  }
2531  else if(_dbDriver)
2532  {
2533  _dbDriver->getCalibration(jter->first, models, stereoModel);
2534  }
2535 
2536  bool stereo=false;
2537  if(stereoModel.isValidForProjection())
2538  {
2539  stereo = true;
2540  models.clear();
2541  models.push_back(stereoModel.left());
2542  }
2543  else if(models.size() == 0 || !models[0].isValidForProjection())
2544  {
2545  models.clear();
2546  }
2547 
2548  if(!jter->second.isNull() && models.size())
2549  {
2550  cv::Mat depth;
2551  bool blurryImage = false;
2552  bool getDepth = !stereo && _ui->doubleSpinBox_meshingTextureMaxDepthError->value() >= 0.0f;
2553  cv::Mat img;
2554  std::vector<float> velocity;
2555  if(models[0].imageWidth() == 0 || models[0].imageHeight() == 0)
2556  {
2557  // we are using an old database format (image size not saved in calibrations), we should
2558  // uncompress images to get their size
2559  if(cacheHasCompressedImage)
2560  {
2561  cachedSignatures.find(jter->first)->sensorData().uncompressDataConst(&img, getDepth?&depth:0);
2562  velocity = cachedSignatures.find(jter->first)->getVelocity();
2563  }
2564  else if(_dbDriver)
2565  {
2566  SensorData data;
2567  _dbDriver->getNodeData(jter->first, data, true, false, false, false);
2568  data.uncompressDataConst(&img, getDepth?&depth:0);
2569 
2570  if(_ui->checkBox_cameraFilter->isChecked() &&
2571  (_ui->doubleSpinBox_cameraFilterVel->value()>0.0 || _ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
2572  {
2573  Transform p,gt;
2574  int m,w;
2575  std::string l;
2576  double s;
2577  GPS gps;
2578  _dbDriver->getNodeInfo(jter->first, p, m, w, l, s, gt, velocity, gps);
2579  }
2580  }
2581  cv::Size imageSize = img.size();
2582  imageSize.width /= models.size();
2583  for(unsigned int i=0; i<models.size(); ++i)
2584  {
2585  models[i].setImageSize(imageSize);
2586  }
2587  }
2588  else
2589  {
2590  bool getImg = _ui->checkBox_cameraFilter->isChecked() && _ui->doubleSpinBox_laplacianVariance->value()>0.0;
2591  // get just the depth
2592  if(cacheHasCompressedImage)
2593  {
2594  cachedSignatures.find(jter->first)->sensorData().uncompressDataConst(getImg?&img:0, getDepth?&depth:0);
2595  velocity = cachedSignatures.find(jter->first)->getVelocity();
2596  }
2597  else if(_dbDriver)
2598  {
2599  SensorData data;
2600  _dbDriver->getNodeData(jter->first, data, true, false, false, false);
2601  data.uncompressDataConst(getImg?&img:0, getDepth?&depth:0);
2602 
2603  if(_ui->checkBox_cameraFilter->isChecked() &&
2604  (_ui->doubleSpinBox_cameraFilterVel->value()>0.0 || _ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
2605  {
2606  Transform p,gt;
2607  int m,w;
2608  std::string l;
2609  double s;
2610  GPS gps;
2611  _dbDriver->getNodeInfo(jter->first, p, m, w, l, s, gt, velocity, gps);
2612  }
2613  }
2614  }
2615  if(_ui->checkBox_cameraFilter->isChecked())
2616  {
2617  std::string msg;
2618  if(!blurryImage &&
2619  (_ui->doubleSpinBox_cameraFilterVel->value()>0.0 || _ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
2620  {
2621  if(velocity.size() == 6)
2622  {
2623  float transVel = uMax3(fabs(velocity[0]), fabs(velocity[1]), fabs(velocity[2]));
2624  float rotVel = uMax3(fabs(velocity[3]), fabs(velocity[4]), fabs(velocity[5]));
2625  if(_ui->doubleSpinBox_cameraFilterVel->value()>0.0 && transVel > _ui->doubleSpinBox_cameraFilterVel->value())
2626  {
2627  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());
2628  blurryImage = true;
2629  }
2630  else if(_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0 && rotVel > _ui->doubleSpinBox_cameraFilterVelRad->value())
2631  {
2632  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());
2633  blurryImage = true;
2634  }
2635  }
2636  else
2637  {
2638  UWARN("Camera motion filtering is set, but velocity of camera %d is not available.", jter->first);
2639  }
2640  }
2641 
2642  if(!blurryImage && !img.empty() && _ui->doubleSpinBox_laplacianVariance->value()>0.0)
2643  {
2644  cv::Mat imgLaplacian;
2645  cv::Laplacian(img, imgLaplacian, CV_16S);
2646  cv::Mat m, s;
2647  cv::meanStdDev(imgLaplacian, m, s);
2648  double stddev_pxl = s.at<double>(0);
2649  double var = stddev_pxl*stddev_pxl;
2650  if(var < _ui->doubleSpinBox_laplacianVariance->value())
2651  {
2652  blurryImage = true;
2653  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());
2654  }
2655  }
2656  if(blurryImage)
2657  {
2658  _progressDialog->appendText(msg.c_str());
2659  QApplication::processEvents();
2660  ++ignoredCameras;
2661  }
2662  }
2663 
2664  if(!blurryImage && models[0].imageWidth() != 0 && models[0].imageHeight() != 0)
2665  {
2666  cameraPoses.insert(std::make_pair(jter->first, jter->second));
2667  cameraModels.insert(std::make_pair(jter->first, models));
2668  if(!depth.empty())
2669  {
2670  cameraDepths.insert(std::make_pair(jter->first, depth));
2671  }
2672  }
2673  }
2674  }
2675  }
2676  if(ignoredCameras > (int)validCameras.size()/2)
2677  {
2678  std::string msg = uFormat("More than 50%% of the cameras (%d/%d) have been filtered for "
2679  "too fast motion and/or blur level. You may adjust the corresponding thresholds.",
2680  ignoredCameras, (int)validCameras.size());
2681  UWARN(msg.c_str());
2682  _progressDialog->appendText(msg.c_str(), Qt::darkYellow);
2683  _progressDialog->setAutoClose(false);
2684  QApplication::processEvents();
2685  }
2686 
2687  if(cameraPoses.size() && iter->second->polygons.size())
2688  {
2689  pcl::TextureMesh::Ptr textureMesh(new pcl::TextureMesh);
2690  std::map<int, std::vector<int> >::iterator oter = organizedIndices.find(iter->first);
2691  std::map<int, cv::Size>::iterator ster = organizedCloudSizes.find(iter->first);
2692  if(iter->first != 0 && oter != organizedIndices.end())
2693  {
2694  UASSERT(ster!=organizedCloudSizes.end()&&ster->first == oter->first);
2695  UDEBUG("Texture by pixels");
2696  textureMesh->cloud = iter->second->cloud;
2697  textureMesh->tex_polygons.push_back(iter->second->polygons);
2698  int w = ster->second.width;
2699  int h = ster->second.height;
2700  UASSERT(w > 1 && h > 1);
2701  if(textureMesh->tex_polygons.size() && textureMesh->tex_polygons[0].size())
2702  {
2703  textureMesh->tex_coordinates.resize(1);
2704 
2705  //tex_coordinates should be linked to polygon vertices
2706  int polygonSize = (int)textureMesh->tex_polygons[0][0].vertices.size();
2707  textureMesh->tex_coordinates[0].resize(polygonSize*textureMesh->tex_polygons[0].size());
2708  for(unsigned int i=0; i<textureMesh->tex_polygons[0].size(); ++i)
2709  {
2710  const pcl::Vertices & vertices = textureMesh->tex_polygons[0][i];
2711  UASSERT(polygonSize == (int)vertices.vertices.size());
2712  for(int k=0; k<polygonSize; ++k)
2713  {
2714  //uv
2715  UASSERT(vertices.vertices[k] < oter->second.size());
2716  int originalVertex = oter->second[vertices.vertices[k]];
2717  textureMesh->tex_coordinates[0][i*polygonSize+k] = Eigen::Vector2f(
2718  float(originalVertex % w) / float(w), // u
2719  float(h - originalVertex / w) / float(h)); // v
2720  }
2721  }
2722 
2723  pcl::TexMaterial mesh_material;
2724  mesh_material.tex_d = 1.0f;
2725  mesh_material.tex_Ns = 75.0f;
2726  mesh_material.tex_illum = 1;
2727 
2728  std::stringstream tex_name;
2729  tex_name << "material_" << iter->first;
2730  tex_name >> mesh_material.tex_name;
2731 
2732  mesh_material.tex_file = uFormat("%d", iter->first);
2733  textureMesh->tex_materials.push_back(mesh_material);
2734  }
2735  else
2736  {
2737  UWARN("No polygons for mesh %d!?", iter->first);
2738  }
2739  }
2740  else
2741  {
2742  UDEBUG("Texture by projection");
2743 
2744  if(cameraPoses.size() && _ui->checkBox_cameraFilter->isChecked())
2745  {
2746  int before = (int)cameraPoses.size();
2747  cameraPoses = graph::radiusPosesFiltering(cameraPoses,
2748  _ui->doubleSpinBox_cameraFilterRadius->value(),
2749  _ui->doubleSpinBox_cameraFilterAngle->value());
2750  for(std::map<int, std::vector<CameraModel> >::iterator modelIter = cameraModels.begin(); modelIter!=cameraModels.end();)
2751  {
2752  if(cameraPoses.find(modelIter->first)==cameraPoses.end())
2753  {
2754  cameraModels.erase(modelIter++);
2755  cameraDepths.erase(modelIter->first);
2756  }
2757  else
2758  {
2759  ++modelIter;
2760  }
2761  }
2762  _progressDialog->appendText(tr("Camera filtering: keeping %1/%2 cameras for texturing.").arg(cameraPoses.size()).arg(before));
2763  QApplication::processEvents();
2764  uSleep(100);
2765  QApplication::processEvents();
2766  }
2767 
2768  if(_canceled)
2769  {
2770  return false;
2771  }
2772 
2773  TexturingState texturingState(_progressDialog, true);
2774  _progressDialog->setMaximumSteps(_progressDialog->maximumSteps()+iter->second->polygons.size()/10000+1);
2775  if(cameraModels.size() && cameraModels.begin()->second.size()>1)
2776  {
2777  _progressDialog->setMaximumSteps(_progressDialog->maximumSteps()+cameraModels.size()*(cameraModels.begin()->second.size()-1));
2778  }
2779 
2780  std::vector<float> roiRatios;
2781  QStringList strings = _ui->lineEdit_meshingTextureRoiRatios->text().split(' ');
2782  if(!_ui->lineEdit_meshingTextureRoiRatios->text().isEmpty())
2783  {
2784  if(strings.size()==4)
2785  {
2786  roiRatios.resize(4);
2787  roiRatios[0]=strings[0].toDouble();
2788  roiRatios[1]=strings[1].toDouble();
2789  roiRatios[2]=strings[2].toDouble();
2790  roiRatios[3]=strings[3].toDouble();
2791  if(!(roiRatios[0]>=0.0f && roiRatios[0]<=1.0f &&
2792  roiRatios[1]>=0.0f && roiRatios[1]<=1.0f &&
2793  roiRatios[2]>=0.0f && roiRatios[2]<=1.0f &&
2794  roiRatios[3]>=0.0f && roiRatios[3]<=1.0f))
2795  {
2796  roiRatios.clear();
2797  }
2798  }
2799  if(roiRatios.empty())
2800  {
2801  QString msg = tr("Wrong ROI format. Region of Interest (ROI) must have 4 values [left right top bottom] between 0 and 1 separated by space (%1), ignoring it for texturing...").arg(_ui->lineEdit_meshingTextureRoiRatios->text());
2802  UWARN(msg.toStdString().c_str());
2803  _progressDialog->appendText(msg, Qt::darkYellow);
2804  _progressDialog->setAutoClose(false);
2805  }
2806  }
2807 
2808  textureMesh = util3d::createTextureMesh(
2809  iter->second,
2810  cameraPoses,
2811  cameraModels,
2812  cameraDepths,
2813  _ui->doubleSpinBox_meshingTextureMaxDistance->value(),
2814  _ui->doubleSpinBox_meshingTextureMaxDepthError->value(),
2815  _ui->doubleSpinBox_meshingTextureMaxAngle->value()*M_PI/180.0,
2816  _ui->spinBox_mesh_minTextureClusterSize->value(),
2817  roiRatios,
2818  &texturingState,
2819  cameraPoses.size()>1?&textureVertexToPixels:0); // only get vertexToPixels if merged clouds with multi textures
2820 
2821  if(_canceled)
2822  {
2823  return false;
2824  }
2825 
2826  // Remove occluded polygons (polygons with no texture)
2827  if(_ui->checkBox_cleanMesh->isChecked())
2828  {
2829  unsigned int totalSize = 0;
2830  for(unsigned int t=0; t<textureMesh->tex_polygons.size(); ++t)
2831  {
2832  totalSize+=textureMesh->tex_polygons[t].size();
2833  }
2834 
2835  util3d::cleanTextureMesh(*textureMesh, _ui->spinBox_mesh_minClusterSize->value());
2836 
2837  unsigned int totalSizeAfter = 0;
2838  for(unsigned int t=0; t<textureMesh->tex_polygons.size(); ++t)
2839  {
2840  totalSizeAfter+=textureMesh->tex_polygons[t].size();
2841  }
2842  _progressDialog->appendText(tr("Cleaned texture mesh: %1 -> %2 polygons").arg(totalSize).arg(totalSizeAfter));
2843  }
2844  }
2845 
2846  textureMeshes.insert(std::make_pair(iter->first, textureMesh));
2847  }
2848  else if(cameraPoses.size() == 0)
2849  {
2850  _progressDialog->appendText(tr("No cameras from %1 poses with valid calibration found!").arg(poses.size()), Qt::darkYellow);
2851  _progressDialog->setAutoClose(false);
2852  UWARN("No camera poses!?");
2853  }
2854  else
2855  {
2856  _progressDialog->appendText(tr("No polygons!?"), Qt::darkYellow);
2857  _progressDialog->setAutoClose(false);
2858  UWARN("No polygons!");
2859  }
2860 
2861  _progressDialog->appendText(tr("TextureMesh %1 created [cameras=%2] (%3/%4).").arg(iter->first).arg(cameraPoses.size()).arg(++i).arg(meshes.size()));
2863  QApplication::processEvents();
2864  if(_canceled)
2865  {
2866  return false;
2867  }
2868  }
2869 
2870  if(textureMeshes.size() > 1 && _ui->checkBox_assemble->isChecked())
2871  {
2872  UDEBUG("Concatenate texture meshes");
2873  _progressDialog->appendText(tr("Assembling %1 meshes...").arg(textureMeshes.size()));
2874  QApplication::processEvents();
2875  uSleep(100);
2876  QApplication::processEvents();
2877 
2878  pcl::TextureMesh::Ptr assembledMesh = util3d::concatenateTextureMeshes(uValuesList(textureMeshes));
2879  textureMeshes.clear();
2880  textureMeshes.insert(std::make_pair(0, assembledMesh));
2881  }
2882 
2883  }
2884  UDEBUG("");
2885  return true;
2886  }
2887  return false;
2888 }
2889 
2890 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > ExportCloudsDialog::getClouds(
2891  const std::map<int, Transform> & poses,
2892  const QMap<int, Signature> & cachedSignatures,
2893  const std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
2894  const std::map<int, LaserScan> & cachedScans,
2895  const ParametersMap & parameters,
2896  bool & has2dScans) const
2897 {
2898  has2dScans = false;
2899  std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
2900  int index=1;
2901  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr previousCloud;
2902  pcl::IndicesPtr previousIndices;
2903  Transform previousPose;
2904  for(std::map<int, Transform>::const_iterator iter = poses.begin(); iter!=poses.end() && !_canceled; ++iter, ++index)
2905  {
2906  int points = 0;
2907  int totalIndices = 0;
2908  if(!iter->second.isNull())
2909  {
2910  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2911  pcl::IndicesPtr indices(new std::vector<int>);
2912  Transform localTransform = Transform::getIdentity();
2913  if(_ui->checkBox_regenerate->isChecked())
2914  {
2915  SensorData data;
2916  cv::Mat image, depth;
2917  LaserScan scan;
2918  if(cachedSignatures.contains(iter->first))
2919  {
2920  const Signature & s = cachedSignatures.find(iter->first).value();
2921  data = s.sensorData();
2922  data.uncompressData(
2923  _ui->checkBox_fromDepth->isChecked()?&image:0,
2924  _ui->checkBox_fromDepth->isChecked()?&depth:0,
2925  !_ui->checkBox_fromDepth->isChecked()?&scan:0);
2926  }
2927  else if(_dbDriver)
2928  {
2929  _dbDriver->getNodeData(iter->first, data, _ui->checkBox_fromDepth->isChecked(), !_ui->checkBox_fromDepth->isChecked(), false, false);
2930  data.uncompressData(
2931  _ui->checkBox_fromDepth->isChecked()?&image:0,
2932  _ui->checkBox_fromDepth->isChecked()?&depth:0,
2933  !_ui->checkBox_fromDepth->isChecked()?&scan:0);
2934  }
2935 
2936  if(_ui->checkBox_fromDepth->isChecked() && !image.empty() && !depth.empty())
2937  {
2938  if(_ui->spinBox_fillDepthHoles->value() > 0)
2939  {
2940  depth = util2d::fillDepthHoles(depth, _ui->spinBox_fillDepthHoles->value(), float(_ui->spinBox_fillDepthHolesError->value())/100.f);
2941  }
2942 
2943  if(!_ui->lineEdit_distortionModel->text().isEmpty() &&
2944  QFileInfo(_ui->lineEdit_distortionModel->text()).exists())
2945  {
2947  model.load(_ui->lineEdit_distortionModel->text().toStdString());
2948  depth = depth.clone();// make sure we are not modifying data in cached signatures.
2949  model.undistort(depth);
2950  data.setDepthOrRightRaw(depth);
2951  }
2952 
2953  // bilateral filtering
2954  if(_ui->checkBox_bilateral->isChecked())
2955  {
2956  depth = util2d::fastBilateralFiltering(depth,
2957  _ui->doubleSpinBox_bilateral_sigmaS->value(),
2958  _ui->doubleSpinBox_bilateral_sigmaR->value());
2959  data.setDepthOrRightRaw(depth);
2960  }
2961 
2962  UASSERT(iter->first == data.id());
2963  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
2964  std::vector<float> roiRatios;
2965  if(!_ui->lineEdit_roiRatios->text().isEmpty())
2966  {
2967  QStringList values = _ui->lineEdit_roiRatios->text().split(' ');
2968  if(values.size() == 4)
2969  {
2970  roiRatios.resize(4);
2971  for(int i=0; i<values.size(); ++i)
2972  {
2973  roiRatios[i] = uStr2Float(values[i].toStdString().c_str());
2974  }
2975  }
2976  }
2977  cloudWithoutNormals = util3d::cloudRGBFromSensorData(
2978  data,
2979  _ui->spinBox_decimation->value() == 0?1:_ui->spinBox_decimation->value(),
2980  _ui->doubleSpinBox_maxDepth->value(),
2981  _ui->doubleSpinBox_minDepth->value(),
2982  indices.get(),
2983  parameters,
2984  roiRatios);
2985 
2986  if(cloudWithoutNormals->size())
2987  {
2988  // Don't voxelize if we create organized mesh
2989  if(!(_ui->comboBox_pipeline->currentIndex()==0 && _ui->checkBox_meshing->isChecked()) && _ui->doubleSpinBox_voxelSize_assembled->value()>0.0)
2990  {
2991  cloudWithoutNormals = util3d::voxelize(cloudWithoutNormals, indices, _ui->doubleSpinBox_voxelSize_assembled->value());
2992  indices->resize(cloudWithoutNormals->size());
2993  for(unsigned int i=0; i<indices->size(); ++i)
2994  {
2995  indices->at(i) = i;
2996  }
2997  }
2998 
2999  // view point
3000  Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
3001  if(data.cameraModels().size() && !data.cameraModels()[0].localTransform().isNull())
3002  {
3003  localTransform = data.cameraModels()[0].localTransform();
3004  viewPoint[0] = data.cameraModels()[0].localTransform().x();
3005  viewPoint[1] = data.cameraModels()[0].localTransform().y();
3006  viewPoint[2] = data.cameraModels()[0].localTransform().z();
3007  }
3008  else if(!data.stereoCameraModel().localTransform().isNull())
3009  {
3010  localTransform = data.stereoCameraModel().localTransform();
3011  viewPoint[0] = data.stereoCameraModel().localTransform().x();
3012  viewPoint[1] = data.stereoCameraModel().localTransform().y();
3013  viewPoint[2] = data.stereoCameraModel().localTransform().z();
3014  }
3015 
3016  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
3017  pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
3018 
3019  if(_ui->checkBox_subtraction->isChecked() &&
3020  _ui->doubleSpinBox_subtractPointFilteringRadius->value() > 0.0)
3021  {
3022  pcl::IndicesPtr beforeSubtractionIndices = indices;
3023  if( cloud->size() &&
3024  previousCloud.get() != 0 &&
3025  previousIndices.get() != 0 &&
3026  previousIndices->size() &&
3027  !previousPose.isNull())
3028  {
3029  rtabmap::Transform t = iter->second.inverse() * previousPose;
3030  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformedCloud = rtabmap::util3d::transformPointCloud(previousCloud, t);
3032  cloud,
3033  indices,
3034  transformedCloud,
3035  previousIndices,
3036  _ui->doubleSpinBox_subtractPointFilteringRadius->value(),
3037  _ui->doubleSpinBox_subtractPointFilteringAngle->value(),
3038  _ui->spinBox_subtractFilteringMinPts->value());
3039  }
3040  previousCloud = cloud;
3041  previousIndices = beforeSubtractionIndices;
3042  previousPose = iter->second;
3043  }
3044  }
3045  }
3046  else if(!_ui->checkBox_fromDepth->isChecked() && !scan.isEmpty())
3047  {
3048  bool is2D = scan.is2d();
3049  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
3050  localTransform = Transform::getIdentity();
3051  Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
3052  localTransform = scan.localTransform();
3053  viewPoint[0] = localTransform.x();
3054  viewPoint[1] = localTransform.y();
3055  viewPoint[2] = localTransform.z();
3056 
3057  cloudWithoutNormals = util3d::laserScanToPointCloudRGB(scan, localTransform); // put in base frame by default
3058  if(cloudWithoutNormals->size())
3059  {
3060  if(_ui->doubleSpinBox_voxelSize_assembled->value()>0.0)
3061  {
3062  cloudWithoutNormals = util3d::voxelize(cloudWithoutNormals, _ui->doubleSpinBox_voxelSize_assembled->value());
3063  }
3064  indices->resize(cloudWithoutNormals->size());
3065  for(unsigned int i=0; i<indices->size(); ++i)
3066  {
3067  indices->at(i) = i;
3068  }
3069  pcl::PointCloud<pcl::Normal>::Ptr normals;
3070  if(is2D)
3071  {
3072  // set nan normals
3073  normals.reset(new pcl::PointCloud<pcl::Normal>);
3074  normals->resize(cloudWithoutNormals->size());
3075  for(unsigned int i=0;i<cloudWithoutNormals->size(); ++i)
3076  {
3077  normals->points[i].normal_x =std::numeric_limits<float>::quiet_NaN();
3078  normals->points[i].normal_y =std::numeric_limits<float>::quiet_NaN();
3079  normals->points[i].normal_z =std::numeric_limits<float>::quiet_NaN();
3080  }
3081  has2dScans = true;
3082  }
3083  else
3084  {
3085  normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
3086  }
3087  pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
3088  }
3089  }
3090  else
3091  {
3092  int weight = 0;
3093  if(cachedSignatures.contains(iter->first))
3094  {
3095  const Signature & s = cachedSignatures.find(iter->first).value();
3096  weight = s.getWeight();
3097  }
3098  else if(_dbDriver)
3099  {
3100  _dbDriver->getWeight(iter->first, weight);
3101  }
3102  if(weight>=0) // don't show error for intermediate nodes
3103  {
3104  UERROR("Cloud %d not found in cache!", iter->first);
3105  }
3106  }
3107  }
3108  else if(_ui->checkBox_fromDepth->isChecked() && uContains(cachedClouds, iter->first))
3109  {
3110  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
3111  if(!_ui->checkBox_meshing->isChecked() &&
3112  _ui->doubleSpinBox_voxelSize_assembled->value() > 0.0)
3113  {
3114  cloudWithoutNormals = util3d::voxelize(
3115  cachedClouds.at(iter->first).first,
3116  cachedClouds.at(iter->first).second,
3117  _ui->doubleSpinBox_voxelSize_assembled->value());
3118 
3119  //generate indices for all points (they are all valid)
3120  indices->resize(cloudWithoutNormals->size());
3121  for(unsigned int i=0; i<cloudWithoutNormals->size(); ++i)
3122  {
3123  indices->at(i) = i;
3124  }
3125  }
3126  else
3127  {
3128  cloudWithoutNormals = cachedClouds.at(iter->first).first;
3129  indices = cachedClouds.at(iter->first).second;
3130  }
3131 
3132  // view point
3133  Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
3134  std::vector<CameraModel> models;
3135  StereoCameraModel stereoModel;
3136  if(cachedSignatures.contains(iter->first))
3137  {
3138  const Signature & s = cachedSignatures.find(iter->first).value();
3139  models = s.sensorData().cameraModels();
3140  stereoModel = s.sensorData().stereoCameraModel();
3141  }
3142  else if(_dbDriver)
3143  {
3144  _dbDriver->getCalibration(iter->first, models, stereoModel);
3145  }
3146 
3147  if(models.size() && !models[0].localTransform().isNull())
3148  {
3149  localTransform = models[0].localTransform();
3150  viewPoint[0] = models[0].localTransform().x();
3151  viewPoint[1] = models[0].localTransform().y();
3152  viewPoint[2] = models[0].localTransform().z();
3153  }
3154  else if(!stereoModel.localTransform().isNull())
3155  {
3156  localTransform = stereoModel.localTransform();
3157  viewPoint[0] = stereoModel.localTransform().x();
3158  viewPoint[1] = stereoModel.localTransform().y();
3159  viewPoint[2] = stereoModel.localTransform().z();
3160  }
3161  else
3162  {
3163  _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);
3164  }
3165 
3166  pcl::PointCloud<pcl::Normal>::Ptr normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
3167  pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
3168  }
3169  else if(!_ui->checkBox_fromDepth->isChecked() && uContains(cachedScans, iter->first))
3170  {
3171  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
3172 
3173  localTransform = cachedScans.at(iter->first).localTransform();
3174  Eigen::Vector3f viewPoint(0.0f,0.0f,0.0f);
3175  viewPoint[0] = localTransform.x();
3176  viewPoint[1] = localTransform.y();
3177  viewPoint[2] = localTransform.z();
3178 
3179  bool is2D = cachedScans.at(iter->first).is2d();
3180  cloudWithoutNormals = util3d::laserScanToPointCloudRGB(cachedScans.at(iter->first), cachedScans.at(iter->first).localTransform());
3181  if(cloudWithoutNormals->size())
3182  {
3183  if(_ui->doubleSpinBox_voxelSize_assembled->value()>0.0)
3184  {
3185  cloudWithoutNormals = util3d::voxelize(cloudWithoutNormals, _ui->doubleSpinBox_voxelSize_assembled->value());
3186  }
3187  indices->resize(cloudWithoutNormals->size());
3188  for(unsigned int i=0; i<indices->size(); ++i)
3189  {
3190  indices->at(i) = i;
3191  }
3192 
3193  pcl::PointCloud<pcl::Normal>::Ptr normals;
3194  if(is2D)
3195  {
3196  // set nan normals
3197  normals.reset(new pcl::PointCloud<pcl::Normal>);
3198  normals->resize(cloudWithoutNormals->size());
3199  for(unsigned int i=0;i<cloudWithoutNormals->size(); ++i)
3200  {
3201  normals->points[i].normal_x =std::numeric_limits<float>::quiet_NaN();
3202  normals->points[i].normal_y =std::numeric_limits<float>::quiet_NaN();
3203  normals->points[i].normal_z =std::numeric_limits<float>::quiet_NaN();
3204  }
3205  has2dScans = true;
3206  }
3207  else
3208  {
3209  normals = util3d::computeNormals(cloudWithoutNormals, indices, _ui->spinBox_normalKSearch->value(), _ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
3210  }
3211  pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
3212  }
3213  }
3214  else
3215  {
3216  int weight = 0;
3217  if(cachedSignatures.contains(iter->first))
3218  {
3219  const Signature & s = cachedSignatures.find(iter->first).value();
3220  weight = s.getWeight();
3221  }
3222  else if(_dbDriver)
3223  {
3224  _dbDriver->getWeight(iter->first, weight);
3225  }
3226  if(weight>=0) // don't show error for intermediate nodes
3227  {
3228  _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);
3229  }
3230  }
3231 
3232  if(indices->size())
3233  {
3234  if(_ui->checkBox_filtering->isChecked() &&
3235  _ui->doubleSpinBox_filteringRadius->value() > 0.0f &&
3236  _ui->spinBox_filteringMinNeighbors->value() > 0)
3237  {
3238  indices = util3d::radiusFiltering(cloud, indices, _ui->doubleSpinBox_filteringRadius->value(), _ui->spinBox_filteringMinNeighbors->value());
3239  }
3240 
3241  if((_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex()==2) && cloud->isOrganized())
3242  {
3243  cloud = util3d::transformPointCloud(cloud, localTransform.inverse()); // put back in camera frame
3244  }
3245  else if(_ui->comboBox_frame->isEnabled() && _ui->comboBox_frame->currentIndex()==3)
3246  {
3247  cloud = util3d::transformPointCloud(cloud, localTransform.inverse()); // put back in scan frame
3248  }
3249 
3250  clouds.insert(std::make_pair(iter->first, std::make_pair(cloud, indices)));
3251  points = (int)cloud->size();
3252  totalIndices = (int)indices->size();
3253  }
3254  }
3255  else
3256  {
3257  UERROR("transform is null!?");
3258  }
3259 
3260  if(points>0)
3261  {
3262  if(_ui->checkBox_regenerate->isChecked())
3263  {
3264  _progressDialog->appendText(tr("Generated cloud %1 with %2 points and %3 indices (%4/%5).")
3265  .arg(iter->first).arg(points).arg(totalIndices).arg(index).arg(poses.size()));
3266  }
3267  else
3268  {
3269  _progressDialog->appendText(tr("Copied cloud %1 from cache with %2 points and %3 indices (%4/%5).")
3270  .arg(iter->first).arg(points).arg(totalIndices).arg(index).arg(poses.size()));
3271  }
3272  }
3273  else
3274  {
3275  _progressDialog->appendText(tr("Ignored cloud %1 (%2/%3).").arg(iter->first).arg(index).arg(poses.size()));
3276  }
3278  QApplication::processEvents();
3279  }
3280 
3281  return clouds;
3282 }
3283 
3284 
3286  const QString & workingDirectory,
3287  const std::map<int, Transform> & poses,
3288  const std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds,
3289  bool binaryMode)
3290 {
3291  if(clouds.size() == 1)
3292  {
3293  QString path = QFileDialog::getSaveFileName(this, tr("Save cloud to ..."), workingDirectory+QDir::separator()+"cloud.ply", tr("Point cloud data (*.ply *.pcd)"));
3294  if(!path.isEmpty())
3295  {
3296  if(clouds.begin()->second->size())
3297  {
3298  _progressDialog->appendText(tr("Saving the cloud (%1 points)...").arg(clouds.begin()->second->size()));
3299 
3300  bool success =false;
3301  if(QFileInfo(path).suffix() == "pcd")
3302  {
3303  success = pcl::io::savePCDFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
3304  }
3305  else if(QFileInfo(path).suffix() == "ply")
3306  {
3307  success = pcl::io::savePLYFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
3308  }
3309  else if(QFileInfo(path).suffix() == "")
3310  {
3311  //use ply by default
3312  path += ".ply";
3313  success = pcl::io::savePLYFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
3314  }
3315  else
3316  {
3317  UERROR("Extension not recognized! (%s) Should be one of (*.ply *.pcd).", QFileInfo(path).suffix().toStdString().c_str());
3318  }
3319  if(success)
3320  {
3322  _progressDialog->appendText(tr("Saving the cloud (%1 points)... done.").arg(clouds.begin()->second->size()));
3323 
3324  QMessageBox::information(this, tr("Save successful!"), tr("Cloud saved to \"%1\"").arg(path));
3325  }
3326  else
3327  {
3328  QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
3329  }
3330  }
3331  else
3332  {
3333  QMessageBox::warning(this, tr("Save failed!"), tr("Cloud is empty..."));
3334  }
3335  }
3336  }
3337  else if(clouds.size())
3338  {
3339  QString path = QFileDialog::getExistingDirectory(this, tr("Save clouds to (*.ply *.pcd)..."), workingDirectory, 0);
3340  if(!path.isEmpty())
3341  {
3342  bool ok = false;
3343  QStringList items;
3344  items.push_back("ply");
3345  items.push_back("pcd");
3346  QString suffix = QInputDialog::getItem(this, tr("File format"), tr("Which format?"), items, 0, false, &ok);
3347 
3348  if(ok)
3349  {
3350  QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "cloud", &ok);
3351 
3352  if(ok)
3353  {
3354  for(std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::const_iterator iter=clouds.begin(); iter!=clouds.end(); ++iter)
3355  {
3356  if(iter->second->size())
3357  {
3358  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformedCloud;
3359  transformedCloud = util3d::transformPointCloud(iter->second, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
3360 
3361  QString pathFile = path+QDir::separator()+QString("%1%2.%3").arg(prefix).arg(iter->first).arg(suffix);
3362  bool success =false;
3363  if(suffix == "pcd")
3364  {
3365  success = pcl::io::savePCDFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
3366  }
3367  else if(suffix == "ply")
3368  {
3369  success = pcl::io::savePLYFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
3370  }
3371  else
3372  {
3373  UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
3374  }
3375  if(success)
3376  {
3377  _progressDialog->appendText(tr("Saved cloud %1 (%2 points) to %3.").arg(iter->first).arg(iter->second->size()).arg(pathFile));
3378  }
3379  else
3380  {
3381  _progressDialog->appendText(tr("Failed saving cloud %1 (%2 points) to %3.").arg(iter->first).arg(iter->second->size()).arg(pathFile), Qt::darkRed);
3382  _progressDialog->setAutoClose(false);
3383  }
3384  }
3385  else
3386  {
3387  _progressDialog->appendText(tr("Cloud %1 is empty!").arg(iter->first));
3388  }
3390  QApplication::processEvents();
3391  if(_canceled)
3392  {
3393  return;
3394  }
3395  }
3396  }
3397  }
3398  }
3399  }
3400 }
3401 
3403  const QString & workingDirectory,
3404  const std::map<int, Transform> & poses,
3405  const std::map<int, pcl::PolygonMesh::Ptr> & meshes,
3406  bool binaryMode)
3407 {
3408  if(meshes.size() == 1)
3409  {
3410  QString path = QFileDialog::getSaveFileName(this, tr("Save mesh to ..."), workingDirectory+QDir::separator()+"mesh.ply", tr("Mesh (*.ply)"));
3411  if(!path.isEmpty())
3412  {
3413  if(meshes.begin()->second->polygons.size())
3414  {
3415  _progressDialog->appendText(tr("Saving the mesh (%1 polygons)...").arg(meshes.begin()->second->polygons.size()));
3416  QApplication::processEvents();
3417  uSleep(100);
3418  QApplication::processEvents();
3419 
3420  bool success =false;
3421  if(QFileInfo(path).suffix() == "")
3422  {
3423  path += ".ply";
3424  }
3425 
3426  if(QFileInfo(path).suffix() == "ply")
3427  {
3428  if(binaryMode)
3429  {
3430  success = pcl::io::savePLYFileBinary(path.toStdString(), *meshes.begin()->second) == 0;
3431  }
3432  else
3433  {
3434  success = pcl::io::savePLYFile(path.toStdString(), *meshes.begin()->second) == 0;
3435  }
3436  }
3437  else if(QFileInfo(path).suffix() == "obj")
3438  {
3439  success = pcl::io::saveOBJFile(path.toStdString(), *meshes.begin()->second) == 0;
3440  }
3441  else
3442  {
3443  UERROR("Extension not recognized! (%s) Should be (*.ply).", QFileInfo(path).suffix().toStdString().c_str());
3444  }
3445  if(success)
3446  {
3448  _progressDialog->appendText(tr("Saving the mesh (%1 polygons)... done.").arg(meshes.begin()->second->polygons.size()));
3449 
3450  QMessageBox::information(this, tr("Save successful!"), tr("Mesh saved to \"%1\"").arg(path));
3451  }
3452  else
3453  {
3454  QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
3455  }
3456  }
3457  else
3458  {
3459  QMessageBox::warning(this, tr("Save failed!"), tr("Cloud is empty..."));
3460  }
3461  }
3462  }
3463  else if(meshes.size())
3464  {
3465  QString path = QFileDialog::getExistingDirectory(this, tr("Save meshes to (*.ply *.obj)..."), workingDirectory, 0);
3466  if(!path.isEmpty())
3467  {
3468  bool ok = false;
3469  QStringList items;
3470  items.push_back("ply");
3471  items.push_back("obj");
3472  QString suffix = QInputDialog::getItem(this, tr("File format"), tr("Which format?"), items, 0, false, &ok);
3473 
3474  if(ok)
3475  {
3476  QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "mesh", &ok);
3477 
3478  if(ok)
3479  {
3480  for(std::map<int, pcl::PolygonMesh::Ptr>::const_iterator iter=meshes.begin(); iter!=meshes.end(); ++iter)
3481  {
3482  if(iter->second->polygons.size())
3483  {
3484  pcl::PolygonMesh mesh;
3485  mesh.polygons = iter->second->polygons;
3486  bool isRGB = false;
3487  for(unsigned int i=0; i<iter->second->cloud.fields.size(); ++i)
3488  {
3489  if(iter->second->cloud.fields[i].name.compare("rgb") == 0)
3490  {
3491  isRGB=true;
3492  break;
3493  }
3494  }
3495  if(isRGB)
3496  {
3497  pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZRGB>);
3498  pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
3499  tmp = util3d::transformPointCloud(tmp, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
3500  pcl::toPCLPointCloud2(*tmp, mesh.cloud);
3501  }
3502  else
3503  {
3504  pcl::PointCloud<pcl::PointXYZ>::Ptr tmp(new pcl::PointCloud<pcl::PointXYZ>);
3505  pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
3506  tmp = util3d::transformPointCloud(tmp, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
3507  pcl::toPCLPointCloud2(*tmp, mesh.cloud);
3508  }
3509 
3510  QString pathFile = path+QDir::separator()+QString("%1%2.%3").arg(prefix).arg(iter->first).arg(suffix);
3511  bool success =false;
3512  if(suffix == "ply")
3513  {
3514  if(binaryMode)
3515  {
3516  success = pcl::io::savePLYFileBinary(pathFile.toStdString(), mesh) == 0;
3517  }
3518  else
3519  {
3520  success = pcl::io::savePLYFile(pathFile.toStdString(), mesh) == 0;
3521  }
3522  }
3523  else if(suffix == "obj")
3524  {
3525  success = pcl::io::saveOBJFile(pathFile.toStdString(), mesh) == 0;
3526  }
3527  else
3528  {
3529  UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
3530  }
3531  if(success)
3532  {
3533  _progressDialog->appendText(tr("Saved mesh %1 (%2 polygons) to %3.")
3534  .arg(iter->first).arg(iter->second->polygons.size()).arg(pathFile));
3535  }
3536  else
3537  {
3538  _progressDialog->appendText(tr("Failed saving mesh %1 (%2 polygons) to %3.")
3539  .arg(iter->first).arg(iter->second->polygons.size()).arg(pathFile), Qt::darkRed);
3540  _progressDialog->setAutoClose(false);
3541  }
3542  }
3543  else
3544  {
3545  _progressDialog->appendText(tr("Mesh %1 is empty!").arg(iter->first));
3546  }
3548  QApplication::processEvents();
3549  if(_canceled)
3550  {
3551  return;
3552  }
3553  }
3554  }
3555  }
3556  }
3557  }
3558 }
3559 
3561  const QString & workingDirectory,
3562  const std::map<int, Transform> & poses,
3563  std::map<int, pcl::TextureMesh::Ptr> & meshes,
3564  const QMap<int, Signature> & cachedSignatures,
3565  const std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels)
3566 {
3567  std::map<int, cv::Mat> images;
3568  std::map<int, std::vector<CameraModel> > calibrations;
3569  for(QMap<int, Signature>::const_iterator iter=cachedSignatures.constBegin(); iter!=cachedSignatures.constEnd(); ++iter)
3570  {
3571  std::vector<CameraModel> models;
3572  if(iter->sensorData().cameraModels().size())
3573  {
3574  models = iter->sensorData().cameraModels();
3575  }
3576  else if(iter->sensorData().stereoCameraModel().isValidForProjection())
3577  {
3578  models.push_back(iter->sensorData().stereoCameraModel().left());
3579  }
3580 
3581  if(!models.empty())
3582  {
3583  if(!iter->sensorData().imageRaw().empty())
3584  {
3585  calibrations.insert(std::make_pair(iter.key(), models));
3586  images.insert(std::make_pair(iter.key(), iter->sensorData().imageRaw()));
3587  }
3588  else if(!iter->sensorData().imageCompressed().empty())
3589  {
3590  calibrations.insert(std::make_pair(iter.key(), models));
3591  images.insert(std::make_pair(iter.key(), iter->sensorData().imageCompressed()));
3592  }
3593  }
3594  }
3595  int textureSize = 1024;
3596  if(_ui->comboBox_meshingTextureSize->currentIndex() > 0)
3597  {
3598  textureSize = 128 << _ui->comboBox_meshingTextureSize->currentIndex(); // start at 256
3599  }
3600  int blendingDecimation = 0;
3601  if(_ui->checkBox_blending->isChecked())
3602  {
3603  if(_ui->comboBox_blendingDecimation->currentIndex() > 0)
3604  {
3605  blendingDecimation = 1 << (_ui->comboBox_blendingDecimation->currentIndex()-1);
3606  }
3607  }
3608 
3609  if(meshes.size() == 1)
3610  {
3611  QString path = QFileDialog::getSaveFileName(this, tr("Save texture mesh to ..."), workingDirectory+QDir::separator()+"mesh.obj", tr("Mesh (*.obj)"));
3612  if(!path.isEmpty())
3613  {
3614  if(meshes.begin()->second->tex_materials.size())
3615  {
3616  _progressDialog->appendText(tr("Saving the mesh (with %1 textures)...").arg(meshes.begin()->second->tex_materials.size()));
3617  QApplication::processEvents();
3618  uSleep(100);
3619  QApplication::processEvents();
3620 
3621  bool success =false;
3622  if(QFileInfo(path).suffix() == "")
3623  {
3624  path += ".obj";
3625  }
3626 
3627  pcl::TextureMesh::Ptr mesh = meshes.begin()->second;
3628 
3629  cv::Mat globalTextures;
3630  bool texturesMerged = _ui->comboBox_meshingTextureSize->isEnabled() && _ui->comboBox_meshingTextureSize->currentIndex() > 0;
3631  if(texturesMerged && mesh->tex_materials.size()>1)
3632  {
3633  globalTextures = util3d::mergeTextures(
3634  *mesh,
3635  images,
3636  calibrations,
3637  0,
3638  _dbDriver,
3639  textureSize,
3640  _ui->spinBox_mesh_maxTextures->value(),
3641  textureVertexToPixels,
3642  _ui->checkBox_gainCompensation->isChecked(),
3643  _ui->doubleSpinBox_gainBeta->value(),
3644  _ui->checkBox_gainRGB->isChecked(),
3645  _ui->checkBox_blending->isChecked(),
3646  blendingDecimation,
3647  _ui->spinBox_textureBrightnessContrastRatioLow->value(),
3648  _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
3649  _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked());
3650  }
3651 
3652  bool singleTexture = mesh->tex_materials.size() == 1;
3653  if(!singleTexture)
3654  {
3655  removeDirRecursively(QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName());
3656  QDir(QFileInfo(path).absoluteDir().absolutePath()).mkdir(QFileInfo(path).baseName());
3657  }
3658 
3659  // used for multi camera texturing, to avoid reloading same texture for sub cameras
3660  cv::Mat previousImage;
3661  int previousTextureId = 0;
3662  std::vector<CameraModel> previousCameraModels;
3663 
3664  cv::Size imageSize;
3665  for(unsigned int i=0; i<mesh->tex_materials.size(); ++i)
3666  {
3667  if(!mesh->tex_materials[i].tex_file.empty())
3668  {
3669  // absolute path
3670  QString fullPath;
3671  if(singleTexture)
3672  {
3673  fullPath = QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName()+_ui->comboBox_meshingTextureFormat->currentText();
3674  }
3675  else
3676  {
3677  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();
3678  }
3679  UDEBUG("Saving %s...", fullPath.toStdString().c_str());
3680  if(singleTexture || !QFileInfo(fullPath).exists())
3681  {
3682  std::list<std::string> texFileSplit = uSplit(mesh->tex_materials[i].tex_file, '_');
3683  if(texFileSplit.size() && uIsInteger(texFileSplit.front(), false))
3684  {
3685  int textureId = uStr2Int(texFileSplit.front());
3686  int textureSubCamera = -1;
3687  if(texFileSplit.size() == 2 &&
3688  uIsInteger(texFileSplit.back(), false))
3689  {
3690  textureSubCamera = uStr2Int(texFileSplit.back());
3691  }
3692  cv::Mat image;
3693  std::vector<CameraModel> cameraModels;
3694 
3695  if(textureId == previousTextureId)
3696  {
3697  image = previousImage;
3698  cameraModels = previousCameraModels;
3699  }
3700  else
3701  {
3702  if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
3703  {
3704  cachedSignatures.value(textureId).sensorData().uncompressDataConst(&image, 0);
3705  cameraModels = cachedSignatures.value(textureId).sensorData().cameraModels();
3706  }
3707  else if(_dbDriver)
3708  {
3709  SensorData data;
3710  _dbDriver->getNodeData(textureId, data, true, false, false, false);
3711  data.uncompressDataConst(&image, 0);
3712  StereoCameraModel stereoModel;
3713  _dbDriver->getCalibration(textureId, cameraModels, stereoModel);
3714  }
3715 
3716  previousImage = image;
3717  previousCameraModels = cameraModels;
3718  previousTextureId = textureId;
3719  }
3720  UASSERT(!image.empty());
3721  imageSize = image.size();
3722  if(textureSubCamera>=0)
3723  {
3724  UASSERT(cameraModels.size());
3725  imageSize.width/=cameraModels.size();
3726  image = image.colRange(imageSize.width*textureSubCamera, imageSize.width*(textureSubCamera+1));
3727  }
3728  if(_ui->checkBox_gainCompensation->isChecked() && _compensator && _compensator->getIndex(textureId) >= 0)
3729  {
3730  _compensator->apply(textureId, image, _ui->checkBox_gainRGB->isChecked());
3731  }
3732 
3733  if(!cv::imwrite(fullPath.toStdString(), image))
3734  {
3735  _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
3736  .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
3737  _progressDialog->setAutoClose(false);
3738  }
3739  }
3740  else if(imageSize.height && imageSize.width)
3741  {
3742  // make a blank texture
3743  cv::Mat image = cv::Mat::ones(imageSize, CV_8UC1)*255;
3744  cv::imwrite(fullPath.toStdString(), image);
3745  }
3746  else if(!globalTextures.empty())
3747  {
3748  if(!cv::imwrite(fullPath.toStdString(), globalTextures(cv::Range::all(), cv::Range(i*globalTextures.rows, (i+1)*globalTextures.rows))))
3749  {
3750  _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
3751  .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
3752  _progressDialog->setAutoClose(false);
3753  }
3754  }
3755  else
3756  {
3757  UWARN("Ignored texture %s (no image size set yet)", mesh->tex_materials[i].tex_file.c_str());
3758  }
3759  }
3760  else
3761  {
3762  UWARN("File %s already exists!", fullPath.toStdString().c_str());
3763  }
3764  // relative path
3765  if(singleTexture)
3766  {
3767  mesh->tex_materials[i].tex_file=QFileInfo(path).baseName().toStdString()+_ui->comboBox_meshingTextureFormat->currentText().toStdString();
3768  }
3769  else
3770  {
3771  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();
3772  }
3773  }
3774  }
3775 
3776  success = pcl::io::saveOBJFile(path.toStdString(), *mesh) == 0;
3777  if(success)
3778  {
3780  _progressDialog->appendText(tr("Saving the mesh (with %1 textures)... done.").arg(mesh->tex_materials.size()));
3781 
3782  QMessageBox::information(this, tr("Save successful!"), tr("Mesh saved to \"%1\"").arg(path));
3783  }
3784  else
3785  {
3786  QMessageBox::warning(this, tr("Save failed!"), tr("Failed to save to \"%1\"").arg(path));
3787  }
3788  }
3789  else
3790  {
3791  QMessageBox::warning(this, tr("Save failed!"), tr("No textures..."));
3792  }
3793  }
3794  }
3795  else if(meshes.size())
3796  {
3797  QString path = QFileDialog::getExistingDirectory(this, tr("Save texture meshes to (*.obj)..."), workingDirectory, 0);
3798  if(!path.isEmpty())
3799  {
3800  bool ok = false;
3801  QString prefix = QInputDialog::getText(this, tr("File prefix"), tr("Prefix:"), QLineEdit::Normal, "mesh", &ok);
3802  QString suffix = "obj";
3803 
3804  if(ok)
3805  {
3806  for(std::map<int, pcl::TextureMesh::Ptr>::iterator iter=meshes.begin(); iter!=meshes.end(); ++iter)
3807  {
3808  QString currentPrefix=prefix+QString::number(iter->first);
3809  if(iter->second->tex_materials.size())
3810  {
3811  pcl::TextureMesh::Ptr mesh = iter->second;
3812  cv::Mat globalTextures;
3813  bool texturesMerged = _ui->comboBox_meshingTextureSize->isEnabled() && _ui->comboBox_meshingTextureSize->currentIndex() > 0;
3814  if(texturesMerged && mesh->tex_materials.size()>1)
3815  {
3816  globalTextures = util3d::mergeTextures(
3817  *mesh,
3818  images,
3819  calibrations,
3820  0,
3821  _dbDriver,
3822  textureSize,
3823  _ui->spinBox_mesh_maxTextures->value(),
3824  textureVertexToPixels,
3825  _ui->checkBox_gainCompensation->isChecked(),
3826  _ui->doubleSpinBox_gainBeta->value(),
3827  _ui->checkBox_gainRGB->isChecked(),
3828  _ui->checkBox_blending->isChecked(),
3829  blendingDecimation,
3830  _ui->spinBox_textureBrightnessContrastRatioLow->value(),
3831  _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
3832  _ui->checkBox_exposureFusion->isEnabled() && _ui->checkBox_exposureFusion->isChecked());
3833  }
3834  bool singleTexture = mesh->tex_materials.size() == 1;
3835  if(!singleTexture)
3836  {
3837  removeDirRecursively(path+QDir::separator()+currentPrefix);
3838  QDir(path).mkdir(currentPrefix);
3839  }
3840 
3841  // used for multi camera texturing, to avoid reloading same texture for sub cameras
3842  cv::Mat previousImage;
3843  int previousTextureId = 0;
3844  std::vector<CameraModel> previousCameraModels;
3845 
3846  cv::Size imageSize;
3847  for(unsigned int i=0;i<mesh->tex_materials.size(); ++i)
3848  {
3849  if(!mesh->tex_materials[i].tex_file.empty())
3850  {
3851  std::list<std::string> texFileSplit = uSplit(mesh->tex_materials[i].tex_file, '_');
3852  int textureId = 0;
3853  int textureSubCamera = -1;
3854  if(texFileSplit.size() && uIsInteger(texFileSplit.front(), false))
3855  {
3856  textureId = uStr2Int(texFileSplit.front());
3857  if(texFileSplit.size() == 2 &&
3858  uIsInteger(texFileSplit.back(), false))
3859  {
3860  textureSubCamera = uStr2Int(texFileSplit.back());
3861  }
3862  }
3863 
3864  // absolute path
3865  QString fullPath;
3866  if(singleTexture)
3867  {
3868  mesh->tex_materials[i].tex_file = uNumber2Str(iter->first);
3869  fullPath = path+QDir::separator()+prefix + QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText();
3870  }
3871  else
3872  {
3873  fullPath = path+QDir::separator()+currentPrefix+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText();
3874  }
3875  if(textureId>0)
3876  {
3877  cv::Mat image;
3878  std::vector<CameraModel> cameraModels;
3879 
3880  if(textureId == previousTextureId)
3881  {
3882  image = previousImage;
3883  cameraModels = previousCameraModels;
3884  }
3885  else
3886  {
3887  if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
3888  {
3889  cachedSignatures.value(textureId).sensorData().uncompressDataConst(&image, 0);
3890  cameraModels = cachedSignatures.value(textureId).sensorData().cameraModels();
3891  }
3892  else if(_dbDriver)
3893  {
3894  SensorData data;
3895  _dbDriver->getNodeData(textureId, data, true, false, false, false);
3896  data.uncompressDataConst(&image, 0);
3897  StereoCameraModel stereoModel;
3898  _dbDriver->getCalibration(textureId, cameraModels, stereoModel);
3899  }
3900 
3901  previousImage = image;
3902  previousCameraModels = cameraModels;
3903  previousTextureId = textureId;
3904  }
3905 
3906 
3907  UASSERT(!image.empty());
3908  imageSize = image.size();
3909  if(textureSubCamera>=0)
3910  {
3911  UASSERT(cameraModels.size());
3912  imageSize.width/=cameraModels.size();
3913  image = image.colRange(imageSize.width*textureSubCamera, imageSize.width*(textureSubCamera+1));
3914  }
3915  if(_ui->checkBox_gainCompensation->isChecked() && _compensator && _compensator->getIndex(textureId) >= 0)
3916  {
3917  _compensator->apply(textureId, image, _ui->checkBox_gainRGB->isChecked());
3918  }
3919 
3920  if(!cv::imwrite(fullPath.toStdString(), image))
3921  {
3922  _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
3923  .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
3924  _progressDialog->setAutoClose(false);
3925  }
3926  }
3927  else if(imageSize.height && imageSize.width)
3928  {
3929  // make a blank texture
3930  cv::Mat image = cv::Mat::ones(imageSize, CV_8UC1)*255;
3931  cv::imwrite(fullPath.toStdString(), image);
3932  }
3933  else if(!globalTextures.empty())
3934  {
3935  if(!cv::imwrite(fullPath.toStdString(), globalTextures(cv::Range::all(), cv::Range(i*globalTextures.rows, (i+1)*globalTextures.rows))))
3936  {
3937  _progressDialog->appendText(tr("Failed saving texture \"%1\" to \"%2\".")
3938  .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
3939  _progressDialog->setAutoClose(false);
3940  }
3941  }
3942  else
3943  {
3944  UWARN("Ignored texture %s (no image size set yet)", mesh->tex_materials[i].tex_file.c_str());
3945  }
3946  // relative path
3947  if(singleTexture)
3948  {
3949  mesh->tex_materials[i].tex_file=(prefix+ QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
3950  }
3951  else
3952  {
3953  mesh->tex_materials[i].tex_file=(currentPrefix+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
3954  }
3955  }
3956  }
3957  pcl::PointCloud<pcl::PointNormal>::Ptr tmp(new pcl::PointCloud<pcl::PointNormal>);
3958  pcl::fromPCLPointCloud2(mesh->cloud, *tmp);
3959  tmp = util3d::transformPointCloud(tmp, !_ui->comboBox_frame->isEnabled()||_ui->comboBox_frame->currentIndex()==0?poses.at(iter->first):Transform::getIdentity());
3960  pcl::toPCLPointCloud2(*tmp, mesh->cloud);
3961 
3962  QString pathFile = path+QDir::separator()+QString("%1.%3").arg(currentPrefix).arg(suffix);
3963  bool success =false;
3964  if(suffix == "obj")
3965  {
3966  success = pcl::io::saveOBJFile(pathFile.toStdString(), *mesh) == 0;
3967  }
3968  else
3969  {
3970  UFATAL("Extension not recognized! (%s)", suffix.toStdString().c_str());
3971  }
3972  if(success)
3973  {
3974  _progressDialog->appendText(tr("Saved mesh %1 (%2 textures) to %3.")
3975  .arg(iter->first).arg(mesh->tex_materials.size()).arg(pathFile));
3976  }
3977  else
3978  {
3979  _progressDialog->appendText(tr("Failed saving mesh %1 (%2 textures) to %3.")
3980  .arg(iter->first).arg(mesh->tex_materials.size()).arg(pathFile), Qt::darkRed);
3981  _progressDialog->setAutoClose(false);
3982  }
3983  }
3984  else
3985  {
3986  _progressDialog->appendText(tr("Mesh %1 is empty!").arg(iter->first));
3987  }
3989  QApplication::processEvents();
3990  if(_canceled)
3991  {
3992  return;
3993  }
3994  }
3995  }
3996  }
3997  }
3998 }
3999 
4000 }
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)
pcl::PolygonMesh::Ptr chiselToPolygonMesh(const chisel::MeshMap &meshMap, unsigned char r=100, unsigned char g=100, unsigned char b=100)
void setAutoClose(bool on, int delayedClosingTimeMsec=-1)
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)
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 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:656
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:1045
cv::Mat RTABMAP_EXP cvtDepthToFloat(const cv::Mat &depth16U)
Definition: util2d.cpp:923
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
void setCancelButtonVisible(bool visible)
const LaserScan & laserScanCompressed() const
Definition: SensorData.h:159
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) const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
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)
void RTABMAP_EXP getMinMax3D(const cv::Mat &laserScan, cv::Point3f &min, cv::Point3f &max)
Definition: util3d.cpp:2593
f
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)
static Transform getIdentity()
Definition: Transform.cpp:364
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)
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
bool isEmpty() const
Definition: LaserScan.h:69
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 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)
void getNodeData(int signatureId, SensorData &data, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
Definition: DBDriver.cpp:642
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:41
cv::Mat RTABMAP_EXP fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
Definition: util2d.cpp:1809
void setLighting(bool on)
bool is2d() const
Definition: LaserScan.h:72
Basic mathematics functions.
Some conversion functions.
void setPolygonPicking(bool enabled)
bool getNodeInfo(int signatureId, Transform &pose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruthPose, std::vector< float > &velocity, GPS &gps) const
Definition: DBDriver.cpp:727
const LaserScan & laserScanRaw() const
Definition: SensorData.h:163
void buildPickingLocator(bool enable)
double getGain(int id, double *r=0, double *g=0, double *b=0) const
#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())
void saveClouds(const QString &workingDirectory, const std::map< int, Transform > &poses, const std::map< int, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr > &clouds, bool binaryMode=true)
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
Definition: UStl.h:566
bool addCloud(const std::string &id, const pcl::PCLPointCloud2Ptr &binaryCloud, const Transform &pose, bool rgb, bool hasNormals, bool hasIntensity, const QColor &color=QColor())
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.
void getWeight(int signatureId, int &weight) const
Definition: DBDriver.cpp:793
bool getLaserScanInfo(int signatureId, LaserScan &info) const
Definition: DBDriver.cpp:703
const CameraModel & left() const
std::list< std::list< int > > RTABMAP_EXP clusterPolygons(const std::vector< std::set< int > > &neighborPolygons, int minClusterSize=0)
T uMax3(const T &a, const T &b, const T &c)
Definition: UMath.h:80
bool isNull() const
Definition: Transform.cpp:107
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)
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
int getTextureBrightnessConstrastRatioHigh() const
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:1031
chisel::PointCloudPtr pointCloudRGBToChisel(const typename pcl::PointCloud< PointRGBT > &cloud, const Transform &transform=Transform::getIdentity())
void setCloudPointSize(const std::string &id, int size)
bool getCalibration(int signatureId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) const
Definition: DBDriver.cpp:677
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
void setMaximumSteps(int steps)
Transform localTransform() const
Definition: LaserScan.h:67
int id() const
Definition: SensorData.h:152
int getWeight() const
Definition: Signature.h:74
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 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)
void apply(int id, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, bool rgb=true) const
#define false
Definition: ConvertUTF.c:56
void uSleep(unsigned int ms)
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)
pcl::IndicesPtr RTABMAP_EXP radiusFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:193
std::vector< pcl::Vertices > RTABMAP_EXP filterInvalidPolygons(const std::vector< pcl::Vertices > &polygons)
#define UDEBUG(...)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
SensorData & sensorData()
Definition: Signature.h:134
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(...)
cv::Mat RTABMAP_EXP fillDepthHoles(const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
Definition: util2d.cpp:1434
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
Definition: SensorData.h:194
#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)
const cv::Mat & imageCompressed() const
Definition: SensorData.h:157
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
Transform inverse() const
Definition: Transform.cpp:169
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:942
int getIndex(int id) const
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)
int getTextureBrightnessConstrastRatioLow() const
const Transform & localTransform() const
void setDepthOrRightRaw(const cv::Mat &depthOrImageRaw)
Definition: SensorData.h:165
std::string UTILITE_EXP uFormat(const char *fmt,...)
std::string UTILITE_EXP uNumber2Str(unsigned int number)
Definition: UConversion.cpp:90
CameraModel scaled(double scale) const
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP laserScanToPointCloudRGB(const LaserScan &laserScan, const Transform &transform=Transform(), unsigned char r=255, unsigned char g=255, unsigned char b=255)
Definition: util3d.cpp:2363
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())
Definition: UStl.h:240
std::shared_ptr< chisel::DepthImage< float > > depthImageToChisel(const cv::Mat &image)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:31