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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:58