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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:09