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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sun Dec 1 2024 03:42:45