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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:53