29 #include "ui_exportCloudsDialog.h"
48 #include "rtabmap/core/Version.h"
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>
59 #include <QPushButton>
62 #include <QMessageBox>
63 #include <QFileDialog>
64 #include <QInputDialog>
68 #ifdef RTABMAP_CPUTSDF
69 #include <cpu_tsdf/tsdf_volume_octree.h>
70 #include <cpu_tsdf/marching_cubes_tsdf_octree.h>
73 #ifdef RTABMAP_OPENCHISEL
75 #include <open_chisel/ProjectionIntegrator.h>
76 #include <open_chisel/truncation/QuadraticTruncator.h>
77 #include <open_chisel/weighting/ConstantWeighter.h>
82 #elif defined(RTABMAP_LIBLAS)
95 _ui =
new Ui_ExportCloudsDialog();
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()));
105 _ui->comboBox_upsamplingMethod->setItemData(1, 0, Qt::UserRole - 1);
107 connect(
_ui->checkBox_fromDepth, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
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()));
115 connect(
_ui->comboBox_meshingApproach, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
118 connect(
_ui->checkBox_nodes_filtering, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
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()));
127 connect(
_ui->checkBox_regenerate, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
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()));
154 connect(
_ui->checkBox_bilateral, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
156 connect(
_ui->doubleSpinBox_bilateral_sigmaS, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
157 connect(
_ui->doubleSpinBox_bilateral_sigmaR, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
159 connect(
_ui->checkBox_filtering, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
161 connect(
_ui->doubleSpinBox_filteringRadius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
162 connect(
_ui->spinBox_filteringMinNeighbors, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
164 connect(
_ui->checkBox_assemble, SIGNAL(clicked(
bool)),
this, SIGNAL(
configChanged()));
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()));
171 connect(
_ui->checkBox_subtraction, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
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()));
177 connect(
_ui->checkBox_smoothing, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
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)));
191 connect(
_ui->checkBox_gainCompensation, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
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()));
204 connect(
_ui->checkBox_cameraProjection, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
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)");
222 connect(
_ui->checkBox_meshing, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
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()));
228 connect(
_ui->spinBox_meshMaxPolygons, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
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()));
235 connect(
_ui->comboBox_meshingTextureFormat, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
236 connect(
_ui->comboBox_meshingTextureSize, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
237 connect(
_ui->spinBox_mesh_maxTextures, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
238 connect(
_ui->doubleSpinBox_meshingTextureMaxDistance, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
239 connect(
_ui->doubleSpinBox_meshingTextureMaxDepthError, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
240 connect(
_ui->doubleSpinBox_meshingTextureMaxAngle, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
241 connect(
_ui->spinBox_mesh_minTextureClusterSize, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
242 connect(
_ui->lineEdit_meshingTextureRoiRatios, SIGNAL(textChanged(
const QString &)),
this, SIGNAL(
configChanged()));
243 connect(
_ui->checkBox_distanceToCamPolicy, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
244 connect(
_ui->comboBox_texturingColorPolicy, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
245 connect(
_ui->checkBox_cameraFilter, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
247 connect(
_ui->doubleSpinBox_cameraFilterRadius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
248 connect(
_ui->doubleSpinBox_cameraFilterAngle, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
249 connect(
_ui->doubleSpinBox_cameraFilterVel, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
250 connect(
_ui->doubleSpinBox_cameraFilterVelRad, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
251 connect(
_ui->doubleSpinBox_laplacianVariance, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
252 connect(
_ui->checkBox_multiband, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
254 connect(
_ui->spinBox_multiband_downscale, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
255 connect(
_ui->lineEdit_multiband_nbcontrib, SIGNAL(textChanged(
const QString &)),
this, SIGNAL(
configChanged()));
256 connect(
_ui->comboBox_multiband_unwrap, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
257 connect(
_ui->checkBox_multiband_fillholes, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
258 connect(
_ui->spinBox_multiband_padding, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
259 connect(
_ui->doubleSpinBox_multiband_bestscore, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
260 connect(
_ui->doubleSpinBox_multiband_angle, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
261 connect(
_ui->checkBox_multiband_forcevisible, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
263 connect(
_ui->checkBox_poisson_outputPolygons, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
264 connect(
_ui->checkBox_poisson_manifold, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
265 connect(
_ui->spinBox_poisson_depth, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
266 connect(
_ui->doubleSpinBox_poisson_targetPolygonSize, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
267 connect(
_ui->spinBox_poisson_iso, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
268 connect(
_ui->spinBox_poisson_solver, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
269 connect(
_ui->spinBox_poisson_minDepth, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
270 connect(
_ui->doubleSpinBox_poisson_samples, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
271 connect(
_ui->doubleSpinBox_poisson_pointWeight, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
272 connect(
_ui->doubleSpinBox_poisson_scale, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
274 connect(
_ui->doubleSpinBox_cputsdf_size, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
275 connect(
_ui->doubleSpinBox_cputsdf_resolution, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
276 connect(
_ui->doubleSpinBox_cputsdf_tuncPos, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
277 connect(
_ui->doubleSpinBox_cputsdf_tuncNeg, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
278 connect(
_ui->doubleSpinBox_cputsdf_minWeight, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
279 connect(
_ui->doubleSpinBox_cputsdf_flattenRadius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
280 connect(
_ui->spinBox_cputsdf_randomSplit, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
282 connect(
_ui->checkBox_openchisel_mergeVertices, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
283 connect(
_ui->spinBox_openchisel_chunk_size_x, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
284 connect(
_ui->spinBox_openchisel_chunk_size_y, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
285 connect(
_ui->spinBox_openchisel_chunk_size_z, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
286 connect(
_ui->doubleSpinBox_openchisel_truncation_constant, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
287 connect(
_ui->doubleSpinBox_openchisel_truncation_linear, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
288 connect(
_ui->doubleSpinBox_openchisel_truncation_quadratic, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
289 connect(
_ui->doubleSpinBox_openchisel_truncation_scale, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
290 connect(
_ui->spinBox_openchisel_integration_weight, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
291 connect(
_ui->checkBox_openchisel_use_voxel_carving, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
292 connect(
_ui->doubleSpinBox_openchisel_carving_dist_m, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
293 connect(
_ui->doubleSpinBox_openchisel_near_plane_dist, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
294 connect(
_ui->doubleSpinBox_openchisel_far_plane_dist, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
305 _ui->doubleSpinBox_meshDecimationFactor->setEnabled(
false);
306 _ui->spinBox_meshMaxPolygons->setEnabled(
false);
307 _ui->label_meshDecimation->setEnabled(
false);
308 _ui->label_meshMaxPolygons->setEnabled(
false);
311 #if CV_MAJOR_VERSION < 3
312 _ui->checkBox_exposureFusion->setEnabled(
false);
313 _ui->checkBox_exposureFusion->setChecked(
false);
314 _ui->label_exposureFusion->setEnabled(
false);
326 _ui->groupBox->setVisible(
_ui->comboBox_upsamplingMethod->currentIndex() == 0);
327 _ui->groupBox_2->setVisible(
_ui->comboBox_upsamplingMethod->currentIndex() == 1);
328 _ui->groupBox_3->setVisible(
_ui->comboBox_upsamplingMethod->currentIndex() == 2);
329 _ui->groupBox_4->setVisible(
_ui->comboBox_upsamplingMethod->currentIndex() == 3);
330 _ui->groupBox_5->setVisible(
_ui->comboBox_upsamplingMethod->currentIndex() == 4);
343 _ui->checkBox_assemble->setChecked(
true);
344 _ui->checkBox_assemble->setEnabled(
false);
348 _ui->checkBox_assemble->setEnabled(
true);
361 settings.beginGroup(group);
363 settings.setValue(
"pipeline",
_ui->comboBox_pipeline->currentIndex());
364 settings.setValue(
"from_depth",
_ui->checkBox_fromDepth->isChecked());
365 settings.setValue(
"binary",
_ui->checkBox_binary->isChecked());
366 settings.setValue(
"normals_k",
_ui->spinBox_normalKSearch->value());
367 settings.setValue(
"normals_radius",
_ui->doubleSpinBox_normalRadiusSearch->value());
368 settings.setValue(
"normals_ground_normals_up",
_ui->doubleSpinBox_groundNormalsUp->value());
369 settings.setValue(
"intensity_colormap",
_ui->comboBox_intensityColormap->currentIndex());
371 settings.setValue(
"nodes_filtering",
_ui->checkBox_nodes_filtering->isChecked());
372 settings.setValue(
"nodes_filtering_xmin",
_ui->doubleSpinBox_nodes_filtering_xmin->value());
373 settings.setValue(
"nodes_filtering_xmax",
_ui->doubleSpinBox_nodes_filtering_xmax->value());
374 settings.setValue(
"nodes_filtering_ymin",
_ui->doubleSpinBox_nodes_filtering_ymin->value());
375 settings.setValue(
"nodes_filtering_ymax",
_ui->doubleSpinBox_nodes_filtering_ymax->value());
376 settings.setValue(
"nodes_filtering_zmin",
_ui->doubleSpinBox_nodes_filtering_zmin->value());
377 settings.setValue(
"nodes_filtering_zmax",
_ui->doubleSpinBox_nodes_filtering_zmax->value());
379 settings.setValue(
"regenerate",
_ui->checkBox_regenerate->isChecked());
380 settings.setValue(
"regenerate_decimation",
_ui->spinBox_decimation->value());
381 settings.setValue(
"regenerate_max_depth",
_ui->doubleSpinBox_maxDepth->value());
382 settings.setValue(
"regenerate_min_depth",
_ui->doubleSpinBox_minDepth->value());
383 settings.setValue(
"regenerate_ceiling",
_ui->doubleSpinBox_ceilingHeight->value());
384 settings.setValue(
"regenerate_floor",
_ui->doubleSpinBox_floorHeight->value());
385 settings.setValue(
"regenerate_offaxis_filtering",
_ui->groupBox_offAxisFiltering->isChecked());
386 settings.setValue(
"regenerate_offaxis_filtering_angle",
_ui->doubleSpinBox_offAxisFilteringAngle->value());
387 settings.setValue(
"regenerate_offaxis_filtering_pos_x",
_ui->checkBox_offAxisFilteringPosX->isChecked());
388 settings.setValue(
"regenerate_offaxis_filtering_neg_x",
_ui->checkBox_offAxisFilteringNegX->isChecked());
389 settings.setValue(
"regenerate_offaxis_filtering_pos_y",
_ui->checkBox_offAxisFilteringPosY->isChecked());
390 settings.setValue(
"regenerate_offaxis_filtering_neg_y",
_ui->checkBox_offAxisFilteringNegY->isChecked());
391 settings.setValue(
"regenerate_offaxis_filtering_pos_z",
_ui->checkBox_offAxisFilteringPosZ->isChecked());
392 settings.setValue(
"regenerate_offaxis_filtering_neg_z",
_ui->checkBox_offAxisFilteringNegZ->isChecked());
393 settings.setValue(
"regenerate_footprint_height",
_ui->doubleSpinBox_footprintHeight->value());
394 settings.setValue(
"regenerate_footprint_width",
_ui->doubleSpinBox_footprintWidth->value());
395 settings.setValue(
"regenerate_footprint_length",
_ui->doubleSpinBox_footprintLength->value());
396 settings.setValue(
"regenerate_scan_decimation",
_ui->spinBox_decimation_scan->value());
397 settings.setValue(
"regenerate_scan_max_range",
_ui->doubleSpinBox_rangeMax->value());
398 settings.setValue(
"regenerate_scan_min_range",
_ui->doubleSpinBox_rangeMin->value());
399 settings.setValue(
"regenerate_fill_size",
_ui->spinBox_fillDepthHoles->value());
400 settings.setValue(
"regenerate_fill_error",
_ui->spinBox_fillDepthHolesError->value());
401 settings.setValue(
"regenerate_roi",
_ui->lineEdit_roiRatios->text());
402 settings.setValue(
"regenerate_distortion_model",
_ui->lineEdit_distortionModel->text());
404 settings.setValue(
"bilateral",
_ui->checkBox_bilateral->isChecked());
405 settings.setValue(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value());
406 settings.setValue(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value());
408 settings.setValue(
"filtering",
_ui->checkBox_filtering->isChecked());
409 settings.setValue(
"filtering_radius",
_ui->doubleSpinBox_filteringRadius->value());
410 settings.setValue(
"filtering_min_neighbors",
_ui->spinBox_filteringMinNeighbors->value());
412 settings.setValue(
"assemble",
_ui->checkBox_assemble->isChecked());
413 settings.setValue(
"assemble_voxel",
_ui->doubleSpinBox_voxelSize_assembled->value());
414 settings.setValue(
"assemble_samples",
_ui->spinBox_randomSamples_assembled->value());
415 settings.setValue(
"frame",
_ui->comboBox_frame->currentIndex());
417 settings.setValue(
"subtract",
_ui->checkBox_subtraction->isChecked());
418 settings.setValue(
"subtract_point_radius",
_ui->doubleSpinBox_subtractPointFilteringRadius->value());
419 settings.setValue(
"subtract_point_angle",
_ui->doubleSpinBox_subtractPointFilteringAngle->value());
420 settings.setValue(
"subtract_min_neighbors",
_ui->spinBox_subtractFilteringMinPts->value());
422 settings.setValue(
"mls",
_ui->checkBox_smoothing->isChecked());
423 settings.setValue(
"mls_radius",
_ui->doubleSpinBox_mlsRadius->value());
424 settings.setValue(
"mls_polygonial_order",
_ui->spinBox_polygonialOrder->value());
425 settings.setValue(
"mls_upsampling_method",
_ui->comboBox_upsamplingMethod->currentIndex());
426 settings.setValue(
"mls_upsampling_radius",
_ui->doubleSpinBox_sampleRadius->value());
427 settings.setValue(
"mls_upsampling_step",
_ui->doubleSpinBox_sampleStep->value());
428 settings.setValue(
"mls_point_density",
_ui->spinBox_randomPoints->value());
429 settings.setValue(
"mls_dilation_voxel_size",
_ui->doubleSpinBox_dilationVoxelSize->value());
430 settings.setValue(
"mls_dilation_iterations",
_ui->spinBox_dilationSteps->value());
431 settings.setValue(
"mls_output_voxel_size",
_ui->doubleSpinBox_mls_outputVoxelSize->value());
433 settings.setValue(
"gain",
_ui->checkBox_gainCompensation->isChecked());
434 settings.setValue(
"gain_radius",
_ui->doubleSpinBox_gainRadius->value());
435 settings.setValue(
"gain_overlap",
_ui->doubleSpinBox_gainOverlap->value());
436 settings.setValue(
"gain_beta",
_ui->doubleSpinBox_gainBeta->value());
437 settings.setValue(
"gain_rgb",
_ui->checkBox_gainRGB->isChecked());
438 settings.setValue(
"gain_full",
_ui->checkBox_gainFull->isChecked());
440 settings.setValue(
"cam_proj",
_ui->checkBox_cameraProjection->isChecked());
441 settings.setValue(
"cam_proj_roi_ratios",
_ui->lineEdit_camProjRoiRatios->text());
442 settings.setValue(
"cam_proj_mask",
_ui->lineEdit_camProjMaskFilePath->text());
443 settings.setValue(
"cam_proj_decimation",
_ui->spinBox_camProjDecimation->value());
444 settings.setValue(
"cam_proj_max_distance",
_ui->doubleSpinBox_camProjMaxDistance->value());
445 settings.setValue(
"cam_proj_max_angle",
_ui->doubleSpinBox_camProjMaxAngle->value());
446 settings.setValue(
"cam_proj_distance_policy",
_ui->checkBox_camProjDistanceToCamPolicy->isChecked());
447 settings.setValue(
"cam_proj_keep_points",
_ui->checkBox_camProjKeepPointsNotSeenByCameras->isChecked());
448 settings.setValue(
"cam_proj_recolor_points",
_ui->checkBox_camProjRecolorPoints->isChecked());
449 settings.setValue(
"cam_proj_export_format",
_ui->comboBox_camProjExportCamera->currentIndex());
451 settings.setValue(
"mesh",
_ui->checkBox_meshing->isChecked());
452 settings.setValue(
"mesh_radius",
_ui->doubleSpinBox_gp3Radius->value());
453 settings.setValue(
"mesh_mu",
_ui->doubleSpinBox_gp3Mu->value());
454 settings.setValue(
"mesh_decimation_factor",
_ui->doubleSpinBox_meshDecimationFactor->value());
455 settings.setValue(
"mesh_max_polygons",
_ui->spinBox_meshMaxPolygons->value());
456 settings.setValue(
"mesh_color_radius",
_ui->doubleSpinBox_transferColorRadius->value());
457 settings.setValue(
"mesh_clean",
_ui->checkBox_cleanMesh->isChecked());
458 settings.setValue(
"mesh_min_cluster_size",
_ui->spinBox_mesh_minClusterSize->value());
460 settings.setValue(
"mesh_dense_strategy",
_ui->comboBox_meshingApproach->currentIndex());
462 settings.setValue(
"mesh_texture",
_ui->checkBox_textureMapping->isChecked());
463 settings.setValue(
"mesh_textureFormat",
_ui->comboBox_meshingTextureFormat->currentIndex());
464 settings.setValue(
"mesh_textureSize",
_ui->comboBox_meshingTextureSize->currentIndex());
465 settings.setValue(
"mesh_textureMaxCount",
_ui->spinBox_mesh_maxTextures->value());
466 settings.setValue(
"mesh_textureMaxDistance",
_ui->doubleSpinBox_meshingTextureMaxDistance->value());
467 settings.setValue(
"mesh_textureMaxDepthError",
_ui->doubleSpinBox_meshingTextureMaxDepthError->value());
468 settings.setValue(
"mesh_textureMaxAngle",
_ui->doubleSpinBox_meshingTextureMaxAngle->value());
469 settings.setValue(
"mesh_textureMinCluster",
_ui->spinBox_mesh_minTextureClusterSize->value());
470 settings.setValue(
"mesh_textureRoiRatios",
_ui->lineEdit_meshingTextureRoiRatios->text());
471 settings.setValue(
"mesh_textureDistanceToCamPolicy",
_ui->checkBox_distanceToCamPolicy->isChecked());
472 settings.setValue(
"mesh_textureVertexColorPolicy",
_ui->comboBox_texturingColorPolicy->currentIndex());
473 settings.setValue(
"mesh_textureCameraFiltering",
_ui->checkBox_cameraFilter->isChecked());
474 settings.setValue(
"mesh_textureCameraFilteringRadius",
_ui->doubleSpinBox_cameraFilterRadius->value());
475 settings.setValue(
"mesh_textureCameraFilteringAngle",
_ui->doubleSpinBox_cameraFilterAngle->value());
476 settings.setValue(
"mesh_textureCameraFilteringVel",
_ui->doubleSpinBox_cameraFilterVel->value());
477 settings.setValue(
"mesh_textureCameraFilteringVelRad",
_ui->doubleSpinBox_cameraFilterVelRad->value());
478 settings.setValue(
"mesh_textureCameraFilteringLaplacian",
_ui->doubleSpinBox_laplacianVariance->value());
479 settings.setValue(
"mesh_textureBrightnessConstrastRatioLow",
_ui->spinBox_textureBrightnessContrastRatioLow->value());
480 settings.setValue(
"mesh_textureBrightnessConstrastRatioHigh",
_ui->spinBox_textureBrightnessContrastRatioHigh->value());
481 settings.setValue(
"mesh_textureExposureFusion",
_ui->checkBox_exposureFusion->isChecked());
482 settings.setValue(
"mesh_textureBlending",
_ui->checkBox_blending->isChecked());
483 settings.setValue(
"mesh_textureBlendingDecimation",
_ui->comboBox_blendingDecimation->currentIndex());
484 settings.setValue(
"mesh_textureMultiband",
_ui->checkBox_multiband->isChecked());
485 settings.setValue(
"mesh_textureMultibandDownScale",
_ui->spinBox_multiband_downscale->value());
486 settings.setValue(
"mesh_textureMultibandNbContrib",
_ui->lineEdit_multiband_nbcontrib->text());
487 settings.setValue(
"mesh_textureMultibandUnwrap",
_ui->comboBox_multiband_unwrap->currentIndex());
488 settings.setValue(
"mesh_textureMultibandFillHoles",
_ui->checkBox_multiband_fillholes->isChecked());
489 settings.setValue(
"mesh_textureMultibandPadding",
_ui->spinBox_multiband_padding->value());
490 settings.setValue(
"mesh_textureMultibandBestScoreThr",
_ui->doubleSpinBox_multiband_bestscore->value());
491 settings.setValue(
"mesh_textureMultibandAngleHardThr",
_ui->doubleSpinBox_multiband_angle->value());
492 settings.setValue(
"mesh_textureMultibandForceVisible",
_ui->checkBox_multiband_forcevisible->isChecked());
495 settings.setValue(
"mesh_angle_tolerance",
_ui->doubleSpinBox_mesh_angleTolerance->value());
496 settings.setValue(
"mesh_quad",
_ui->checkBox_mesh_quad->isChecked());
497 settings.setValue(
"mesh_triangle_size",
_ui->spinBox_mesh_triangleSize->value());
499 settings.setValue(
"poisson_outputPolygons",
_ui->checkBox_poisson_outputPolygons->isChecked());
500 settings.setValue(
"poisson_manifold",
_ui->checkBox_poisson_manifold->isChecked());
501 settings.setValue(
"poisson_depth",
_ui->spinBox_poisson_depth->value());
502 settings.setValue(
"poisson_polygon_size",
_ui->doubleSpinBox_poisson_targetPolygonSize->value());
503 settings.setValue(
"poisson_iso",
_ui->spinBox_poisson_iso->value());
504 settings.setValue(
"poisson_solver",
_ui->spinBox_poisson_solver->value());
505 settings.setValue(
"poisson_minDepth",
_ui->spinBox_poisson_minDepth->value());
506 settings.setValue(
"poisson_samples",
_ui->doubleSpinBox_poisson_samples->value());
507 settings.setValue(
"poisson_pointWeight",
_ui->doubleSpinBox_poisson_pointWeight->value());
508 settings.setValue(
"poisson_scale",
_ui->doubleSpinBox_poisson_scale->value());
510 settings.setValue(
"cputsdf_size",
_ui->doubleSpinBox_cputsdf_size->value());
511 settings.setValue(
"cputsdf_resolution",
_ui->doubleSpinBox_cputsdf_resolution->value());
512 settings.setValue(
"cputsdf_truncPos",
_ui->doubleSpinBox_cputsdf_tuncPos->value());
513 settings.setValue(
"cputsdf_truncNeg",
_ui->doubleSpinBox_cputsdf_tuncNeg->value());
514 settings.setValue(
"cputsdf_minWeight",
_ui->doubleSpinBox_cputsdf_minWeight->value());
515 settings.setValue(
"cputsdf_flattenRadius",
_ui->doubleSpinBox_cputsdf_flattenRadius->value());
516 settings.setValue(
"cputsdf_randomSplit",
_ui->spinBox_cputsdf_randomSplit->value());
518 settings.setValue(
"openchisel_merge_vertices",
_ui->checkBox_openchisel_mergeVertices->isChecked());
519 settings.setValue(
"openchisel_chunk_size_x",
_ui->spinBox_openchisel_chunk_size_x->value());
520 settings.setValue(
"openchisel_chunk_size_y",
_ui->spinBox_openchisel_chunk_size_y->value());
521 settings.setValue(
"openchisel_chunk_size_z",
_ui->spinBox_openchisel_chunk_size_z->value());
522 settings.setValue(
"openchisel_truncation_constant",
_ui->doubleSpinBox_openchisel_truncation_constant->value());
523 settings.setValue(
"openchisel_truncation_linear",
_ui->doubleSpinBox_openchisel_truncation_linear->value());
524 settings.setValue(
"openchisel_truncation_quadratic",
_ui->doubleSpinBox_openchisel_truncation_quadratic->value());
525 settings.setValue(
"openchisel_truncation_scale",
_ui->doubleSpinBox_openchisel_truncation_scale->value());
526 settings.setValue(
"openchisel_integration_weight",
_ui->spinBox_openchisel_integration_weight->value());
527 settings.setValue(
"openchisel_use_voxel_carving",
_ui->checkBox_openchisel_use_voxel_carving->isChecked());
528 settings.setValue(
"openchisel_carving_dist_m",
_ui->doubleSpinBox_openchisel_carving_dist_m->value());
529 settings.setValue(
"openchisel_near_plane_dist",
_ui->doubleSpinBox_openchisel_near_plane_dist->value());
530 settings.setValue(
"openchisel_far_plane_dist",
_ui->doubleSpinBox_openchisel_far_plane_dist->value());
542 settings.beginGroup(group);
545 _ui->comboBox_pipeline->setCurrentIndex(settings.value(
"pipeline",
_ui->comboBox_pipeline->currentIndex()).toInt());
546 _ui->checkBox_fromDepth->setChecked(settings.value(
"from_depth",
_ui->checkBox_fromDepth->isChecked()).toBool());
547 _ui->checkBox_binary->setChecked(settings.value(
"binary",
_ui->checkBox_binary->isChecked()).toBool());
548 _ui->spinBox_normalKSearch->setValue(settings.value(
"normals_k",
_ui->spinBox_normalKSearch->value()).toInt());
549 _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value(
"normals_radius",
_ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
550 _ui->doubleSpinBox_groundNormalsUp->setValue(settings.value(
"normals_ground_normals_up",
_ui->doubleSpinBox_groundNormalsUp->value()).toDouble());
551 _ui->comboBox_intensityColormap->setCurrentIndex(settings.value(
"intensity_colormap",
_ui->comboBox_intensityColormap->currentIndex()).toInt());
553 _ui->checkBox_nodes_filtering->setChecked(settings.value(
"nodes_filtering",
_ui->checkBox_nodes_filtering->isChecked()).toBool());
554 _ui->doubleSpinBox_nodes_filtering_xmin->setValue(settings.value(
"nodes_filtering_xmin",
_ui->doubleSpinBox_nodes_filtering_xmin->value()).toInt());
555 _ui->doubleSpinBox_nodes_filtering_xmax->setValue(settings.value(
"nodes_filtering_xmax",
_ui->doubleSpinBox_nodes_filtering_xmax->value()).toInt());
556 _ui->doubleSpinBox_nodes_filtering_ymin->setValue(settings.value(
"nodes_filtering_ymin",
_ui->doubleSpinBox_nodes_filtering_ymin->value()).toInt());
557 _ui->doubleSpinBox_nodes_filtering_ymax->setValue(settings.value(
"nodes_filtering_ymax",
_ui->doubleSpinBox_nodes_filtering_ymax->value()).toInt());
558 _ui->doubleSpinBox_nodes_filtering_zmin->setValue(settings.value(
"nodes_filtering_zmin",
_ui->doubleSpinBox_nodes_filtering_zmin->value()).toInt());
559 _ui->doubleSpinBox_nodes_filtering_zmax->setValue(settings.value(
"nodes_filtering_zmax",
_ui->doubleSpinBox_nodes_filtering_zmax->value()).toInt());
561 _ui->checkBox_regenerate->setChecked(settings.value(
"regenerate",
_ui->checkBox_regenerate->isChecked()).toBool());
562 _ui->spinBox_decimation->setValue(settings.value(
"regenerate_decimation",
_ui->spinBox_decimation->value()).toInt());
563 _ui->doubleSpinBox_maxDepth->setValue(settings.value(
"regenerate_max_depth",
_ui->doubleSpinBox_maxDepth->value()).toDouble());
564 _ui->doubleSpinBox_minDepth->setValue(settings.value(
"regenerate_min_depth",
_ui->doubleSpinBox_minDepth->value()).toDouble());
565 _ui->doubleSpinBox_ceilingHeight->setValue(settings.value(
"regenerate_ceiling",
_ui->doubleSpinBox_ceilingHeight->value()).toDouble());
566 _ui->doubleSpinBox_floorHeight->setValue(settings.value(
"regenerate_floor",
_ui->doubleSpinBox_floorHeight->value()).toDouble());
567 _ui->groupBox_offAxisFiltering->setChecked(settings.value(
"regenerate_offaxis_filtering",
_ui->groupBox_offAxisFiltering->isChecked()).toBool());
568 _ui->doubleSpinBox_offAxisFilteringAngle->setValue(settings.value(
"regenerate_offaxis_filtering_angle",
_ui->doubleSpinBox_offAxisFilteringAngle->value()).toDouble());
569 _ui->checkBox_offAxisFilteringPosX->setChecked(settings.value(
"regenerate_offaxis_filtering_pos_x",
_ui->checkBox_offAxisFilteringPosX->isChecked()).toBool());
570 _ui->checkBox_offAxisFilteringNegX->setChecked(settings.value(
"regenerate_offaxis_filtering_neg_x",
_ui->checkBox_offAxisFilteringNegX->isChecked()).toBool());
571 _ui->checkBox_offAxisFilteringPosY->setChecked(settings.value(
"regenerate_offaxis_filtering_pos_y",
_ui->checkBox_offAxisFilteringPosY->isChecked()).toBool());
572 _ui->checkBox_offAxisFilteringNegY->setChecked(settings.value(
"regenerate_offaxis_filtering_neg_y",
_ui->checkBox_offAxisFilteringNegY->isChecked()).toBool());
573 _ui->checkBox_offAxisFilteringPosZ->setChecked(settings.value(
"regenerate_offaxis_filtering_pos_z",
_ui->checkBox_offAxisFilteringPosZ->isChecked()).toBool());
574 _ui->checkBox_offAxisFilteringNegZ->setChecked(settings.value(
"regenerate_offaxis_filtering_neg_z",
_ui->checkBox_offAxisFilteringNegZ->isChecked()).toBool());
575 _ui->doubleSpinBox_footprintHeight->setValue(settings.value(
"regenerate_footprint_height",
_ui->doubleSpinBox_footprintHeight->value()).toDouble());
576 _ui->doubleSpinBox_footprintWidth->setValue(settings.value(
"regenerate_footprint_width",
_ui->doubleSpinBox_footprintWidth->value()).toDouble());
577 _ui->doubleSpinBox_footprintLength->setValue(settings.value(
"regenerate_footprint_length",
_ui->doubleSpinBox_footprintLength->value()).toDouble());
578 _ui->spinBox_decimation_scan->setValue(settings.value(
"regenerate_scan_decimation",
_ui->spinBox_decimation_scan->value()).toInt());
579 _ui->doubleSpinBox_rangeMax->setValue(settings.value(
"regenerate_scan_max_range",
_ui->doubleSpinBox_rangeMax->value()).toDouble());
580 _ui->doubleSpinBox_rangeMin->setValue(settings.value(
"regenerate_scan_min_range",
_ui->doubleSpinBox_rangeMin->value()).toDouble());
581 _ui->spinBox_fillDepthHoles->setValue(settings.value(
"regenerate_fill_size",
_ui->spinBox_fillDepthHoles->value()).toInt());
582 _ui->spinBox_fillDepthHolesError->setValue(settings.value(
"regenerate_fill_error",
_ui->spinBox_fillDepthHolesError->value()).toInt());
583 _ui->lineEdit_roiRatios->setText(settings.value(
"regenerate_roi",
_ui->lineEdit_roiRatios->text()).toString());
584 _ui->lineEdit_distortionModel->setText(settings.value(
"regenerate_distortion_model",
_ui->lineEdit_distortionModel->text()).toString());
586 _ui->checkBox_bilateral->setChecked(settings.value(
"bilateral",
_ui->checkBox_bilateral->isChecked()).toBool());
587 _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
588 _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
590 _ui->checkBox_filtering->setChecked(settings.value(
"filtering",
_ui->checkBox_filtering->isChecked()).toBool());
591 _ui->doubleSpinBox_filteringRadius->setValue(settings.value(
"filtering_radius",
_ui->doubleSpinBox_filteringRadius->value()).toDouble());
592 _ui->spinBox_filteringMinNeighbors->setValue(settings.value(
"filtering_min_neighbors",
_ui->spinBox_filteringMinNeighbors->value()).toInt());
594 if(
_ui->checkBox_assemble->isEnabled())
596 _ui->checkBox_assemble->setChecked(settings.value(
"assemble",
_ui->checkBox_assemble->isChecked()).toBool());
598 _ui->doubleSpinBox_voxelSize_assembled->setValue(settings.value(
"assemble_voxel",
_ui->doubleSpinBox_voxelSize_assembled->value()).toDouble());
599 _ui->spinBox_randomSamples_assembled->setValue(settings.value(
"assemble_samples",
_ui->spinBox_randomSamples_assembled->value()).toInt());
600 _ui->comboBox_frame->setCurrentIndex(settings.value(
"frame",
_ui->comboBox_frame->currentIndex()).toInt());
602 _ui->checkBox_subtraction->setChecked(settings.value(
"subtract",
_ui->checkBox_subtraction->isChecked()).toBool());
603 _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(settings.value(
"subtract_point_radius",
_ui->doubleSpinBox_subtractPointFilteringRadius->value()).toDouble());
604 _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(settings.value(
"subtract_point_angle",
_ui->doubleSpinBox_subtractPointFilteringAngle->value()).toDouble());
605 _ui->spinBox_subtractFilteringMinPts->setValue(settings.value(
"subtract_min_neighbors",
_ui->spinBox_subtractFilteringMinPts->value()).toInt());
607 _ui->checkBox_smoothing->setChecked(settings.value(
"mls",
_ui->checkBox_smoothing->isChecked()).toBool());
608 _ui->doubleSpinBox_mlsRadius->setValue(settings.value(
"mls_radius",
_ui->doubleSpinBox_mlsRadius->value()).toDouble());
609 _ui->spinBox_polygonialOrder->setValue(settings.value(
"mls_polygonial_order",
_ui->spinBox_polygonialOrder->value()).toInt());
610 _ui->comboBox_upsamplingMethod->setCurrentIndex(settings.value(
"mls_upsampling_method",
_ui->comboBox_upsamplingMethod->currentIndex()).toInt());
611 _ui->doubleSpinBox_sampleRadius->setValue(settings.value(
"mls_upsampling_radius",
_ui->doubleSpinBox_sampleRadius->value()).toDouble());
612 _ui->doubleSpinBox_sampleStep->setValue(settings.value(
"mls_upsampling_step",
_ui->doubleSpinBox_sampleStep->value()).toDouble());
613 _ui->spinBox_randomPoints->setValue(settings.value(
"mls_point_density",
_ui->spinBox_randomPoints->value()).toInt());
614 _ui->doubleSpinBox_dilationVoxelSize->setValue(settings.value(
"mls_dilation_voxel_size",
_ui->doubleSpinBox_dilationVoxelSize->value()).toDouble());
615 _ui->spinBox_dilationSteps->setValue(settings.value(
"mls_dilation_iterations",
_ui->spinBox_dilationSteps->value()).toInt());
616 _ui->doubleSpinBox_mls_outputVoxelSize->setValue(settings.value(
"mls_output_voxel_size",
_ui->doubleSpinBox_mls_outputVoxelSize->value()).toInt());
618 _ui->checkBox_gainCompensation->setChecked(settings.value(
"gain",
_ui->checkBox_gainCompensation->isChecked()).toBool());
619 _ui->doubleSpinBox_gainRadius->setValue(settings.value(
"gain_radius",
_ui->doubleSpinBox_gainRadius->value()).toDouble());
620 _ui->doubleSpinBox_gainOverlap->setValue(settings.value(
"gain_overlap",
_ui->doubleSpinBox_gainOverlap->value()).toDouble());
621 _ui->doubleSpinBox_gainBeta->setValue(settings.value(
"gain_beta",
_ui->doubleSpinBox_gainBeta->value()).toDouble());
622 _ui->checkBox_gainRGB->setChecked(settings.value(
"gain_rgb",
_ui->checkBox_gainRGB->isChecked()).toBool());
623 _ui->checkBox_gainFull->setChecked(settings.value(
"gain_full",
_ui->checkBox_gainFull->isChecked()).toBool());
625 _ui->checkBox_cameraProjection->setChecked(settings.value(
"cam_proj",
_ui->checkBox_cameraProjection->isChecked()).toBool());
626 _ui->lineEdit_camProjRoiRatios->setText(settings.value(
"cam_proj_roi_ratios",
_ui->lineEdit_camProjRoiRatios->text()).toString());
627 _ui->lineEdit_camProjMaskFilePath->setText(settings.value(
"cam_proj_mask",
_ui->lineEdit_camProjMaskFilePath->text()).toString());
628 _ui->spinBox_camProjDecimation->setValue(settings.value(
"cam_proj_decimation",
_ui->spinBox_camProjDecimation->value()).toInt());
629 _ui->doubleSpinBox_camProjMaxDistance->setValue(settings.value(
"cam_proj_max_distance",
_ui->doubleSpinBox_camProjMaxDistance->value()).toDouble());
630 _ui->doubleSpinBox_camProjMaxAngle->setValue(settings.value(
"cam_proj_max_angle",
_ui->doubleSpinBox_camProjMaxAngle->value()).toDouble());
631 _ui->checkBox_camProjDistanceToCamPolicy->setChecked(settings.value(
"cam_proj_distance_policy",
_ui->checkBox_camProjDistanceToCamPolicy->isChecked()).toBool());
632 _ui->checkBox_camProjKeepPointsNotSeenByCameras->setChecked(settings.value(
"cam_proj_keep_points",
_ui->checkBox_camProjKeepPointsNotSeenByCameras->isChecked()).toBool());
633 _ui->checkBox_camProjRecolorPoints->setChecked(settings.value(
"cam_proj_recolor_points",
_ui->checkBox_camProjRecolorPoints->isChecked()).toBool());
634 _ui->comboBox_camProjExportCamera->setCurrentIndex(settings.value(
"cam_proj_export_format",
_ui->comboBox_camProjExportCamera->currentIndex()).toInt());
636 _ui->checkBox_meshing->setChecked(settings.value(
"mesh",
_ui->checkBox_meshing->isChecked()).toBool());
637 _ui->doubleSpinBox_gp3Radius->setValue(settings.value(
"mesh_radius",
_ui->doubleSpinBox_gp3Radius->value()).toDouble());
638 _ui->doubleSpinBox_gp3Mu->setValue(settings.value(
"mesh_mu",
_ui->doubleSpinBox_gp3Mu->value()).toDouble());
639 _ui->doubleSpinBox_meshDecimationFactor->setValue(settings.value(
"mesh_decimation_factor",
_ui->doubleSpinBox_meshDecimationFactor->value()).toDouble());
640 _ui->spinBox_meshMaxPolygons->setValue(settings.value(
"mesh_max_polygons",
_ui->spinBox_meshMaxPolygons->value()).toDouble());
641 _ui->doubleSpinBox_transferColorRadius->setValue(settings.value(
"mesh_color_radius",
_ui->doubleSpinBox_transferColorRadius->value()).toDouble());
642 _ui->checkBox_cleanMesh->setChecked(settings.value(
"mesh_clean",
_ui->checkBox_cleanMesh->isChecked()).toBool());
643 _ui->spinBox_mesh_minClusterSize->setValue(settings.value(
"mesh_min_cluster_size",
_ui->spinBox_mesh_minClusterSize->value()).toInt());
645 _ui->comboBox_meshingApproach->setCurrentIndex(settings.value(
"mesh_dense_strategy",
_ui->comboBox_meshingApproach->currentIndex()).toInt());
647 _ui->checkBox_textureMapping->setChecked(settings.value(
"mesh_texture",
_ui->checkBox_textureMapping->isChecked()).toBool());
648 _ui->comboBox_meshingTextureFormat->setCurrentIndex(settings.value(
"mesh_textureFormat",
_ui->comboBox_meshingTextureFormat->currentIndex()).toInt());
649 _ui->comboBox_meshingTextureSize->setCurrentIndex(settings.value(
"mesh_textureSize",
_ui->comboBox_meshingTextureSize->currentIndex()).toInt());
650 _ui->spinBox_mesh_maxTextures->setValue(settings.value(
"mesh_textureMaxCount",
_ui->spinBox_mesh_maxTextures->value()).toInt());
651 _ui->doubleSpinBox_meshingTextureMaxDistance->setValue(settings.value(
"mesh_textureMaxDistance",
_ui->doubleSpinBox_meshingTextureMaxDistance->value()).toDouble());
652 _ui->doubleSpinBox_meshingTextureMaxDepthError->setValue(settings.value(
"mesh_textureMaxDepthError",
_ui->doubleSpinBox_meshingTextureMaxDepthError->value()).toDouble());
653 _ui->doubleSpinBox_meshingTextureMaxAngle->setValue(settings.value(
"mesh_textureMaxAngle",
_ui->doubleSpinBox_meshingTextureMaxAngle->value()).toDouble());
654 _ui->spinBox_mesh_minTextureClusterSize->setValue(settings.value(
"mesh_textureMinCluster",
_ui->spinBox_mesh_minTextureClusterSize->value()).toDouble());
655 _ui->lineEdit_meshingTextureRoiRatios->setText(settings.value(
"mesh_textureRoiRatios",
_ui->lineEdit_meshingTextureRoiRatios->text()).toString());
656 _ui->checkBox_distanceToCamPolicy->setChecked(settings.value(
"mesh_textureDistanceToCamPolicy",
_ui->checkBox_distanceToCamPolicy->isChecked()).toBool());
657 _ui->comboBox_texturingColorPolicy->setCurrentIndex(settings.value(
"mesh_textureVertexColorPolicy",
_ui->comboBox_texturingColorPolicy->currentIndex()).toInt());
658 _ui->checkBox_cameraFilter->setChecked(settings.value(
"mesh_textureCameraFiltering",
_ui->checkBox_cameraFilter->isChecked()).toBool());
659 _ui->doubleSpinBox_cameraFilterRadius->setValue(settings.value(
"mesh_textureCameraFilteringRadius",
_ui->doubleSpinBox_cameraFilterRadius->value()).toDouble());
660 _ui->doubleSpinBox_cameraFilterAngle->setValue(settings.value(
"mesh_textureCameraFilteringAngle",
_ui->doubleSpinBox_cameraFilterAngle->value()).toDouble());
661 _ui->doubleSpinBox_cameraFilterVel->setValue(settings.value(
"mesh_textureCameraFilteringVel",
_ui->doubleSpinBox_cameraFilterVel->value()).toDouble());
662 _ui->doubleSpinBox_cameraFilterVelRad->setValue(settings.value(
"mesh_textureCameraFilteringVelRad",
_ui->doubleSpinBox_cameraFilterVelRad->value()).toDouble());
663 _ui->doubleSpinBox_laplacianVariance->setValue(settings.value(
"mesh_textureCameraFilteringLaplacian",
_ui->doubleSpinBox_laplacianVariance->value()).toDouble());
664 _ui->spinBox_textureBrightnessContrastRatioLow->setValue(settings.value(
"mesh_textureBrightnessConstrastRatioLow",
_ui->spinBox_textureBrightnessContrastRatioLow->value()).toDouble());
665 _ui->spinBox_textureBrightnessContrastRatioHigh->setValue(settings.value(
"mesh_textureBrightnessConstrastRatioHigh",
_ui->spinBox_textureBrightnessContrastRatioHigh->value()).toDouble());
666 if(
_ui->checkBox_exposureFusion->isEnabled())
668 _ui->checkBox_exposureFusion->setChecked(settings.value(
"mesh_textureExposureFusion",
_ui->checkBox_exposureFusion->isChecked()).toBool());
670 _ui->checkBox_blending->setChecked(settings.value(
"mesh_textureBlending",
_ui->checkBox_blending->isChecked()).toBool());
671 _ui->comboBox_blendingDecimation->setCurrentIndex(settings.value(
"mesh_textureBlendingDecimation",
_ui->comboBox_blendingDecimation->currentIndex()).toInt());
672 _ui->checkBox_multiband->setChecked(settings.value(
"mesh_textureMultiband",
_ui->checkBox_multiband->isChecked()).toBool());
673 _ui->spinBox_multiband_downscale->setValue(settings.value(
"mesh_textureMultibandDownScale",
_ui->spinBox_multiband_downscale->value()).toInt());
674 _ui->lineEdit_multiband_nbcontrib->setText(settings.value(
"mesh_textureMultibandNbContrib",
_ui->lineEdit_multiband_nbcontrib->text()).toString());
675 _ui->comboBox_multiband_unwrap->setCurrentIndex(settings.value(
"mesh_textureMultibandUnwrap",
_ui->comboBox_multiband_unwrap->currentIndex()).toInt());
676 _ui->checkBox_multiband_fillholes->setChecked(settings.value(
"mesh_textureMultibandFillHoles",
_ui->checkBox_multiband_fillholes->isChecked()).toBool());
677 _ui->spinBox_multiband_padding->setValue(settings.value(
"mesh_textureMultibandPadding",
_ui->spinBox_multiband_padding->value()).toInt());
678 _ui->doubleSpinBox_multiband_bestscore->setValue(settings.value(
"mesh_textureMultibandBestScoreThr",
_ui->doubleSpinBox_multiband_bestscore->value()).toDouble());
679 _ui->doubleSpinBox_multiband_angle->setValue(settings.value(
"mesh_textureMultibandAngleHardThr",
_ui->doubleSpinBox_multiband_angle->value()).toDouble());
680 _ui->checkBox_multiband_forcevisible->setChecked(settings.value(
"mesh_textureMultibandForceVisible",
_ui->checkBox_multiband_forcevisible->isChecked()).toBool());
682 _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value(
"mesh_angle_tolerance",
_ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
683 _ui->checkBox_mesh_quad->setChecked(settings.value(
"mesh_quad",
_ui->checkBox_mesh_quad->isChecked()).toBool());
684 _ui->spinBox_mesh_triangleSize->setValue(settings.value(
"mesh_triangle_size",
_ui->spinBox_mesh_triangleSize->value()).toInt());
686 _ui->checkBox_poisson_outputPolygons->setChecked(settings.value(
"poisson_outputPolygons",
_ui->checkBox_poisson_outputPolygons->isChecked()).toBool());
687 _ui->checkBox_poisson_manifold->setChecked(settings.value(
"poisson_manifold",
_ui->checkBox_poisson_manifold->isChecked()).toBool());
688 _ui->spinBox_poisson_depth->setValue(settings.value(
"poisson_depth",
_ui->spinBox_poisson_depth->value()).toInt());
689 _ui->doubleSpinBox_poisson_targetPolygonSize->setValue(settings.value(
"poisson_polygon_size",
_ui->doubleSpinBox_poisson_targetPolygonSize->value()).toDouble());
690 _ui->spinBox_poisson_iso->setValue(settings.value(
"poisson_iso",
_ui->spinBox_poisson_iso->value()).toInt());
691 _ui->spinBox_poisson_solver->setValue(settings.value(
"poisson_solver",
_ui->spinBox_poisson_solver->value()).toInt());
692 _ui->spinBox_poisson_minDepth->setValue(settings.value(
"poisson_minDepth",
_ui->spinBox_poisson_minDepth->value()).toInt());
693 _ui->doubleSpinBox_poisson_samples->setValue(settings.value(
"poisson_samples",
_ui->doubleSpinBox_poisson_samples->value()).toDouble());
694 _ui->doubleSpinBox_poisson_pointWeight->setValue(settings.value(
"poisson_pointWeight",
_ui->doubleSpinBox_poisson_pointWeight->value()).toDouble());
695 _ui->doubleSpinBox_poisson_scale->setValue(settings.value(
"poisson_scale",
_ui->doubleSpinBox_poisson_scale->value()).toDouble());
697 _ui->doubleSpinBox_cputsdf_size->setValue(settings.value(
"cputsdf_size",
_ui->doubleSpinBox_cputsdf_size->value()).toDouble());
698 _ui->doubleSpinBox_cputsdf_resolution->setValue(settings.value(
"cputsdf_resolution",
_ui->doubleSpinBox_cputsdf_resolution->value()).toDouble());
699 _ui->doubleSpinBox_cputsdf_tuncPos->setValue(settings.value(
"cputsdf_truncPos",
_ui->doubleSpinBox_cputsdf_tuncPos->value()).toDouble());
700 _ui->doubleSpinBox_cputsdf_tuncNeg->setValue(settings.value(
"cputsdf_truncNeg",
_ui->doubleSpinBox_cputsdf_tuncNeg->value()).toDouble());
701 _ui->doubleSpinBox_cputsdf_minWeight->setValue(settings.value(
"cputsdf_minWeight",
_ui->doubleSpinBox_cputsdf_minWeight->value()).toDouble());
702 _ui->doubleSpinBox_cputsdf_flattenRadius->setValue(settings.value(
"cputsdf_flattenRadius",
_ui->doubleSpinBox_cputsdf_flattenRadius->value()).toDouble());
703 _ui->spinBox_cputsdf_randomSplit->setValue(settings.value(
"cputsdf_randomSplit",
_ui->spinBox_cputsdf_randomSplit->value()).toInt());
705 _ui->checkBox_openchisel_mergeVertices->setChecked(settings.value(
"openchisel_merge_vertices",
_ui->checkBox_openchisel_mergeVertices->isChecked()).toBool());
706 _ui->spinBox_openchisel_chunk_size_x->setValue(settings.value(
"openchisel_chunk_size_x",
_ui->spinBox_openchisel_chunk_size_x->value()).toInt());
707 _ui->spinBox_openchisel_chunk_size_y->setValue(settings.value(
"openchisel_chunk_size_y",
_ui->spinBox_openchisel_chunk_size_y->value()).toInt());
708 _ui->spinBox_openchisel_chunk_size_z->setValue(settings.value(
"openchisel_chunk_size_z",
_ui->spinBox_openchisel_chunk_size_z->value()).toInt());
709 _ui->doubleSpinBox_openchisel_truncation_constant->setValue(settings.value(
"openchisel_truncation_constant",
_ui->doubleSpinBox_openchisel_truncation_constant->value()).toDouble());
710 _ui->doubleSpinBox_openchisel_truncation_linear->setValue(settings.value(
"openchisel_truncation_linear",
_ui->doubleSpinBox_openchisel_truncation_linear->value()).toDouble());
711 _ui->doubleSpinBox_openchisel_truncation_quadratic->setValue(settings.value(
"openchisel_truncation_quadratic",
_ui->doubleSpinBox_openchisel_truncation_quadratic->value()).toDouble());
712 _ui->doubleSpinBox_openchisel_truncation_scale->setValue(settings.value(
"openchisel_truncation_scale",
_ui->doubleSpinBox_openchisel_truncation_scale->value()).toDouble());
713 _ui->spinBox_openchisel_integration_weight->setValue(settings.value(
"openchisel_integration_weight",
_ui->spinBox_openchisel_integration_weight->value()).toInt());
714 _ui->checkBox_openchisel_use_voxel_carving->setChecked(settings.value(
"openchisel_use_voxel_carving",
_ui->checkBox_openchisel_use_voxel_carving->isChecked()).toBool());
715 _ui->doubleSpinBox_openchisel_carving_dist_m->setValue(settings.value(
"openchisel_carving_dist_m",
_ui->doubleSpinBox_openchisel_carving_dist_m->value()).toDouble());
716 _ui->doubleSpinBox_openchisel_near_plane_dist->setValue(settings.value(
"openchisel_near_plane_dist",
_ui->doubleSpinBox_openchisel_near_plane_dist->value()).toDouble());
717 _ui->doubleSpinBox_openchisel_far_plane_dist->setValue(settings.value(
"openchisel_far_plane_dist",
_ui->doubleSpinBox_openchisel_far_plane_dist->value()).toDouble());
730 _ui->comboBox_pipeline->setCurrentIndex(1);
731 _ui->checkBox_fromDepth->setChecked(
true);
732 _ui->checkBox_binary->setChecked(
true);
733 _ui->spinBox_normalKSearch->setValue(20);
734 _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
735 _ui->doubleSpinBox_groundNormalsUp->setValue(0.0);
736 _ui->comboBox_intensityColormap->setCurrentIndex(0);
738 _ui->checkBox_nodes_filtering->setChecked(
false);
739 _ui->doubleSpinBox_nodes_filtering_xmin->setValue(0);
740 _ui->doubleSpinBox_nodes_filtering_xmax->setValue(0);
741 _ui->doubleSpinBox_nodes_filtering_ymin->setValue(0);
742 _ui->doubleSpinBox_nodes_filtering_ymax->setValue(0);
743 _ui->doubleSpinBox_nodes_filtering_zmin->setValue(0);
744 _ui->doubleSpinBox_nodes_filtering_zmax->setValue(0);
746 _ui->checkBox_regenerate->setChecked(
_dbDriver!=0?
true:
false);
747 _ui->spinBox_decimation->setValue(1);
748 _ui->doubleSpinBox_maxDepth->setValue(4);
749 _ui->doubleSpinBox_minDepth->setValue(0);
750 _ui->doubleSpinBox_ceilingHeight->setValue(0);
751 _ui->doubleSpinBox_floorHeight->setValue(0);
752 _ui->groupBox_offAxisFiltering->setChecked(
false);
753 _ui->doubleSpinBox_offAxisFilteringAngle->setValue(10);
754 _ui->checkBox_offAxisFilteringPosX->setChecked(
true);
755 _ui->checkBox_offAxisFilteringNegX->setChecked(
true);
756 _ui->checkBox_offAxisFilteringPosY->setChecked(
true);
757 _ui->checkBox_offAxisFilteringNegY->setChecked(
true);
758 _ui->checkBox_offAxisFilteringPosZ->setChecked(
true);
759 _ui->checkBox_offAxisFilteringNegZ->setChecked(
true);
760 _ui->doubleSpinBox_footprintHeight->setValue(0);
761 _ui->doubleSpinBox_footprintLength->setValue(0);
762 _ui->doubleSpinBox_footprintWidth->setValue(0);
763 _ui->spinBox_decimation_scan->setValue(1);
764 _ui->doubleSpinBox_rangeMax->setValue(0);
765 _ui->doubleSpinBox_rangeMin->setValue(0);
766 _ui->spinBox_fillDepthHoles->setValue(0);
767 _ui->spinBox_fillDepthHolesError->setValue(2);
768 _ui->lineEdit_roiRatios->setText(
"0.0 0.0 0.0 0.0");
769 _ui->lineEdit_distortionModel->setText(
"");
771 _ui->checkBox_bilateral->setChecked(
false);
772 _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
773 _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
775 _ui->checkBox_filtering->setChecked(
false);
776 _ui->doubleSpinBox_filteringRadius->setValue(0.00);
777 _ui->spinBox_filteringMinNeighbors->setValue(5);
779 _ui->checkBox_assemble->setChecked(
true);
780 _ui->doubleSpinBox_voxelSize_assembled->setValue(0.01);
781 _ui->spinBox_randomSamples_assembled->setValue(0);
782 _ui->comboBox_frame->setCurrentIndex(0);
784 _ui->checkBox_subtraction->setChecked(
false);
785 _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(0.02);
786 _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(0);
787 _ui->spinBox_subtractFilteringMinPts->setValue(5);
789 _ui->checkBox_smoothing->setChecked(
false);
790 _ui->doubleSpinBox_mlsRadius->setValue(0.04);
791 _ui->spinBox_polygonialOrder->setValue(2);
792 _ui->comboBox_upsamplingMethod->setCurrentIndex(0);
793 _ui->doubleSpinBox_sampleRadius->setValue(0.01);
794 _ui->doubleSpinBox_sampleStep->setValue(0.005);
795 _ui->spinBox_randomPoints->setValue(10);
796 _ui->doubleSpinBox_dilationVoxelSize->setValue(0.005);
797 _ui->spinBox_dilationSteps->setValue(1);
798 _ui->doubleSpinBox_mls_outputVoxelSize->setValue(0);
800 _ui->checkBox_gainCompensation->setChecked(
false);
801 _ui->doubleSpinBox_gainRadius->setValue(0.02);
802 _ui->doubleSpinBox_gainOverlap->setValue(0.0);
803 _ui->doubleSpinBox_gainBeta->setValue(10);
804 _ui->checkBox_gainRGB->setChecked(
true);
805 _ui->checkBox_gainFull->setChecked(
false);
807 _ui->checkBox_cameraProjection->setChecked(
false);
808 _ui->lineEdit_camProjRoiRatios->setText(
"0.0 0.0 0.0 0.0");
809 _ui->lineEdit_camProjMaskFilePath->setText(
"");
810 _ui->spinBox_camProjDecimation->setValue(1);
811 _ui->doubleSpinBox_camProjMaxDistance->setValue(0);
812 _ui->doubleSpinBox_camProjMaxAngle->setValue(0);
813 _ui->checkBox_camProjDistanceToCamPolicy->setChecked(
true);
814 _ui->checkBox_camProjKeepPointsNotSeenByCameras->setChecked(
false);
815 _ui->checkBox_camProjRecolorPoints->setChecked(
true);
816 _ui->comboBox_camProjExportCamera->setCurrentIndex(0);
818 _ui->checkBox_meshing->setChecked(
false);
819 _ui->doubleSpinBox_gp3Radius->setValue(0.2);
820 _ui->doubleSpinBox_gp3Mu->setValue(2.5);
821 _ui->doubleSpinBox_meshDecimationFactor->setValue(0.0);
822 _ui->spinBox_meshMaxPolygons->setValue(0);
823 _ui->doubleSpinBox_transferColorRadius->setValue(0.05);
824 _ui->checkBox_cleanMesh->setChecked(
true);
825 _ui->spinBox_mesh_minClusterSize->setValue(0);
827 _ui->comboBox_meshingApproach->setCurrentIndex(1);
829 _ui->checkBox_textureMapping->setChecked(
false);
830 _ui->comboBox_meshingTextureFormat->setCurrentIndex(0);
831 _ui->comboBox_meshingTextureSize->setCurrentIndex(6);
832 _ui->spinBox_mesh_maxTextures->setValue(1);
833 _ui->doubleSpinBox_meshingTextureMaxDistance->setValue(3.0);
834 _ui->doubleSpinBox_meshingTextureMaxDepthError->setValue(0.0);
835 _ui->doubleSpinBox_meshingTextureMaxAngle->setValue(0.0);
836 _ui->spinBox_mesh_minTextureClusterSize->setValue(50);
837 _ui->lineEdit_meshingTextureRoiRatios->setText(
"0.0 0.0 0.0 0.0");
838 _ui->checkBox_distanceToCamPolicy->setChecked(
false);
839 _ui->comboBox_texturingColorPolicy->setCurrentIndex(0);
840 _ui->checkBox_cameraFilter->setChecked(
false);
841 _ui->doubleSpinBox_cameraFilterRadius->setValue(0);
842 _ui->doubleSpinBox_cameraFilterAngle->setValue(30);
843 _ui->doubleSpinBox_cameraFilterVel->setValue(0);
844 _ui->doubleSpinBox_cameraFilterVelRad->setValue(0);
845 _ui->doubleSpinBox_laplacianVariance->setValue(0);
846 _ui->spinBox_textureBrightnessContrastRatioLow->setValue(0);
847 _ui->spinBox_textureBrightnessContrastRatioHigh->setValue(5);
848 _ui->checkBox_exposureFusion->setChecked(
false);
849 _ui->checkBox_blending->setChecked(
true);
850 _ui->comboBox_blendingDecimation->setCurrentIndex(0);
851 _ui->checkBox_multiband->setChecked(
false);
852 _ui->spinBox_multiband_downscale->setValue(2);
853 _ui->lineEdit_multiband_nbcontrib->setText(
"1 5 10 0");
854 _ui->comboBox_multiband_unwrap->setCurrentIndex(0);
855 _ui->checkBox_multiband_fillholes->setChecked(
false);
856 _ui->spinBox_multiband_padding->setValue(5);
857 _ui->doubleSpinBox_multiband_bestscore->setValue(0.1);
858 _ui->doubleSpinBox_multiband_angle->setValue(90.0);
859 _ui->checkBox_multiband_forcevisible->setChecked(
false);
862 _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
863 _ui->checkBox_mesh_quad->setChecked(
false);
864 _ui->spinBox_mesh_triangleSize->setValue(1);
866 _ui->checkBox_poisson_outputPolygons->setChecked(
false);
867 _ui->checkBox_poisson_manifold->setChecked(
true);
868 _ui->spinBox_poisson_depth->setValue(0);
869 _ui->doubleSpinBox_poisson_targetPolygonSize->setValue(0.03);
870 _ui->spinBox_poisson_iso->setValue(8);
871 _ui->spinBox_poisson_solver->setValue(8);
872 _ui->spinBox_poisson_minDepth->setValue(5);
873 _ui->doubleSpinBox_poisson_samples->setValue(1.0);
874 _ui->doubleSpinBox_poisson_pointWeight->setValue(4.0);
875 _ui->doubleSpinBox_poisson_scale->setValue(1.1);
877 _ui->doubleSpinBox_cputsdf_size->setValue(12.0);
878 _ui->doubleSpinBox_cputsdf_resolution->setValue(0.01);
879 _ui->doubleSpinBox_cputsdf_tuncPos->setValue(0.03);
880 _ui->doubleSpinBox_cputsdf_tuncNeg->setValue(0.03);
881 _ui->doubleSpinBox_cputsdf_minWeight->setValue(0);
882 _ui->doubleSpinBox_cputsdf_flattenRadius->setValue(0.005);
883 _ui->spinBox_cputsdf_randomSplit->setValue(1);
885 _ui->checkBox_openchisel_mergeVertices->setChecked(
true);
886 _ui->spinBox_openchisel_chunk_size_x->setValue(16);
887 _ui->spinBox_openchisel_chunk_size_y->setValue(16);
888 _ui->spinBox_openchisel_chunk_size_z->setValue(16);
889 _ui->doubleSpinBox_openchisel_truncation_constant->setValue(0.001504);
890 _ui->doubleSpinBox_openchisel_truncation_linear->setValue(0.00152);
891 _ui->doubleSpinBox_openchisel_truncation_quadratic->setValue(0.0019);
892 _ui->doubleSpinBox_openchisel_truncation_scale->setValue(10.0);
893 _ui->spinBox_openchisel_integration_weight->setValue(1);
894 _ui->checkBox_openchisel_use_voxel_carving->setChecked(
false);
895 _ui->doubleSpinBox_openchisel_carving_dist_m->setValue(0.05);
896 _ui->doubleSpinBox_openchisel_near_plane_dist->setValue(0.05);
897 _ui->doubleSpinBox_openchisel_far_plane_dist->setValue(1.1);
908 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Load Settings"),
_workingDirectory, tr(
"Config (*.ini)"));
911 QSettings settings(
path, QSettings::IniFormat);
912 settings.beginGroup(
"Gui");
913 settings.beginGroup(this->objectName());
922 QString
path = QFileDialog::getSaveFileName(
this, tr(
"Save Settings"),
_workingDirectory, tr(
"Config (*.ini)"));
925 QSettings settings(
path, QSettings::IniFormat);
926 settings.beginGroup(
"Gui");
927 settings.beginGroup(this->objectName());
936 if(!
_ui->checkBox_fromDepth->isChecked())
938 _ui->comboBox_pipeline->setCurrentIndex(1);
939 _ui->comboBox_pipeline->setEnabled(
false);
940 _ui->comboBox_frame->setItemData(2, 0,Qt::UserRole - 1);
941 _ui->comboBox_frame->setItemData(3, 1|32,Qt::UserRole - 1);
942 if(
_ui->comboBox_frame->currentIndex() == 2)
944 _ui->comboBox_frame->setCurrentIndex(0);
949 _ui->comboBox_pipeline->setEnabled(
true);
950 _ui->comboBox_frame->setItemData(2, 1|32,Qt::UserRole - 1);
951 _ui->comboBox_frame->setItemData(3, 0,Qt::UserRole - 1);
952 if(
_ui->comboBox_frame->currentIndex() == 3)
954 _ui->comboBox_frame->setCurrentIndex(0);
957 _ui->comboBox_intensityColormap->setVisible(!
_ui->checkBox_fromDepth->isChecked() && !
_ui->checkBox_binary->isEnabled());
958 _ui->comboBox_intensityColormap->setEnabled(!
_ui->checkBox_fromDepth->isChecked() && !
_ui->checkBox_binary->isEnabled());
959 _ui->label_intensityColormap->setVisible(!
_ui->checkBox_fromDepth->isChecked() && !
_ui->checkBox_binary->isEnabled());
961 _ui->checkBox_smoothing->setVisible(
_ui->comboBox_pipeline->currentIndex() == 1);
962 _ui->checkBox_smoothing->setEnabled(
_ui->comboBox_pipeline->currentIndex() == 1);
963 _ui->label_smoothing->setVisible(
_ui->comboBox_pipeline->currentIndex() == 1);
965 _ui->comboBox_frame->setEnabled(!
_ui->checkBox_assemble->isChecked() &&
_ui->checkBox_binary->isEnabled());
966 _ui->comboBox_frame->setVisible(
_ui->comboBox_frame->isEnabled());
967 _ui->label_frame->setVisible(
_ui->comboBox_frame->isEnabled());
968 _ui->checkBox_gainCompensation->setEnabled(!(
_ui->comboBox_frame->isEnabled() &&
_ui->comboBox_frame->currentIndex() == 2));
969 _ui->checkBox_gainCompensation->setVisible(
_ui->checkBox_gainCompensation->isEnabled());
970 _ui->label_gainCompensation->setVisible(
_ui->checkBox_gainCompensation->isEnabled());
972 _ui->checkBox_cameraProjection->setEnabled(
_ui->checkBox_assemble->isChecked() && !
_ui->checkBox_meshing->isChecked());
973 _ui->label_cameraProjection->setEnabled(
_ui->checkBox_cameraProjection->isEnabled());
975 _ui->groupBox_nodes_filtering->setVisible(
_ui->checkBox_nodes_filtering->isChecked());
976 _ui->groupBox_regenerate->setVisible(
_ui->checkBox_regenerate->isChecked() &&
_ui->checkBox_fromDepth->isChecked());
977 _ui->groupBox_regenerateScans->setVisible(
_ui->checkBox_regenerate->isChecked() && !
_ui->checkBox_fromDepth->isChecked());
978 _ui->groupBox_bilateral->setVisible(
_ui->checkBox_bilateral->isChecked());
979 _ui->groupBox_filtering->setVisible(
_ui->checkBox_filtering->isChecked());
980 _ui->groupBox_gain->setVisible(
_ui->checkBox_gainCompensation->isEnabled() &&
_ui->checkBox_gainCompensation->isChecked());
981 _ui->groupBox_cameraProjection->setVisible(
_ui->checkBox_cameraProjection->isEnabled() &&
_ui->checkBox_cameraProjection->isChecked());
982 _ui->groupBox_mls->setVisible(
_ui->checkBox_smoothing->isEnabled() &&
_ui->checkBox_smoothing->isChecked());
983 _ui->groupBox_meshing->setVisible(
_ui->checkBox_meshing->isChecked());
984 _ui->groupBox_subtraction->setVisible(
_ui->checkBox_subtraction->isChecked());
985 _ui->groupBox_textureMapping->setVisible(
_ui->checkBox_textureMapping->isChecked());
986 _ui->groupBox_cameraFilter->setVisible(
_ui->checkBox_cameraFilter->isChecked());
987 _ui->groupBox_multiband->setVisible(
_ui->checkBox_multiband->isChecked());
990 if(
_ui->checkBox_meshing->isChecked())
993 _ui->comboBox_meshingApproach->setItemData(0,
_ui->comboBox_pipeline->currentIndex() == 1?1 | 32:0,Qt::UserRole - 1);
996 _ui->comboBox_meshingApproach->setItemData(1,
_ui->comboBox_pipeline->currentIndex() == 1 &&
_ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
999 #ifdef RTABMAP_CPUTSDF
1000 _ui->comboBox_meshingApproach->setItemData(2,
_ui->comboBox_pipeline->currentIndex() == 0 &&
_ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
1002 _ui->comboBox_meshingApproach->setItemData(2, 0, Qt::UserRole - 1);
1006 _ui->comboBox_meshingApproach->setItemData(3,
_ui->comboBox_pipeline->currentIndex() == 0?1 | 32:0,Qt::UserRole - 1);
1009 #ifdef RTABMAP_OPENCHISEL
1010 _ui->comboBox_meshingApproach->setItemData(4,
_ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
1012 _ui->comboBox_meshingApproach->setItemData(4, 0, Qt::UserRole - 1);
1015 if(
_ui->comboBox_pipeline->currentIndex() == 0 &&
_ui->comboBox_meshingApproach->currentIndex()<2)
1017 _ui->comboBox_meshingApproach->setCurrentIndex(3);
1019 if(
_ui->comboBox_pipeline->currentIndex() == 1 && (
_ui->comboBox_meshingApproach->currentIndex()==2 ||
_ui->comboBox_meshingApproach->currentIndex()==3))
1021 _ui->comboBox_meshingApproach->setCurrentIndex(1);
1023 if(!
_ui->checkBox_assemble->isChecked())
1025 _ui->comboBox_meshingApproach->setCurrentIndex(
_ui->comboBox_pipeline->currentIndex() == 1?0:3);
1028 _ui->checkBox_poisson_outputPolygons->setDisabled(
1029 _ui->checkBox_binary->isEnabled() ||
1030 _ui->doubleSpinBox_meshDecimationFactor->value()!=0.0 ||
1031 _ui->spinBox_meshMaxPolygons->value()!=0 ||
1032 _ui->checkBox_textureMapping->isChecked());
1033 _ui->label_outputPolygons->setEnabled(
_ui->checkBox_poisson_outputPolygons->isEnabled());
1035 _ui->checkBox_cleanMesh->setEnabled(
_ui->comboBox_pipeline->currentIndex() == 1);
1036 _ui->label_meshClean->setEnabled(
_ui->comboBox_pipeline->currentIndex() == 1);
1038 _ui->groupBox_gp3->setVisible(
_ui->comboBox_pipeline->currentIndex() == 1 &&
_ui->comboBox_meshingApproach->currentIndex()==0);
1039 _ui->groupBox_poisson->setVisible(
_ui->comboBox_pipeline->currentIndex() == 1 &&
_ui->comboBox_meshingApproach->currentIndex()==1);
1040 _ui->groupBox_cputsdf->setVisible(
_ui->comboBox_pipeline->currentIndex() == 0 &&
_ui->comboBox_meshingApproach->currentIndex()==2);
1041 _ui->groupBox_organized->setVisible(
_ui->comboBox_pipeline->currentIndex() == 0 &&
_ui->comboBox_meshingApproach->currentIndex()==3);
1042 _ui->groupBox_openchisel->setVisible(
_ui->comboBox_meshingApproach->currentIndex()==4);
1045 _ui->doubleSpinBox_meshDecimationFactor->setEnabled(
_ui->comboBox_meshingApproach->currentIndex()!=3);
1046 _ui->label_meshDecimation->setEnabled(
_ui->comboBox_meshingApproach->currentIndex()!=3);
1047 _ui->spinBox_meshMaxPolygons->setEnabled(
_ui->comboBox_meshingApproach->currentIndex()!=3);
1048 _ui->label_meshMaxPolygons->setEnabled(
_ui->comboBox_meshingApproach->currentIndex()!=3);
1051 #ifndef RTABMAP_ALICE_VISION
1052 _ui->checkBox_multiband->setEnabled(
false);
1054 _ui->checkBox_multiband->setEnabled(
_ui->checkBox_binary->isEnabled());
1056 _ui->label_multiband->setEnabled(
_ui->checkBox_multiband->isEnabled());
1062 QString dir =
_ui->lineEdit_distortionModel->text();
1067 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Distortion model (*.bin *.txt)"));
1070 _ui->lineEdit_distortionModel->setText(
path);
1076 QString dir =
_ui->lineEdit_camProjMaskFilePath->text();
1081 QString
path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Mask (grayscale) (*.png *.pgm *bmp)"));
1084 _ui->lineEdit_camProjMaskFilePath->setText(
path);
1090 _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(
false);
1091 _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(
true);
1092 _ui->checkBox_binary->setVisible(
true);
1093 _ui->checkBox_binary->setEnabled(
true);
1094 _ui->label_binaryFile->setVisible(
true);
1095 _ui->checkBox_mesh_quad->setVisible(
false);
1096 _ui->checkBox_mesh_quad->setEnabled(
false);
1097 _ui->label_quad->setVisible(
false);
1103 _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(
true);
1104 _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(
false);
1105 _ui->checkBox_binary->setVisible(
false);
1106 _ui->checkBox_binary->setEnabled(
false);
1107 _ui->label_binaryFile->setVisible(
false);
1108 _ui->checkBox_mesh_quad->setVisible(
true);
1109 _ui->checkBox_mesh_quad->setEnabled(
true);
1110 _ui->label_quad->setVisible(
true);
1116 if(
_ui->checkBox_nodes_filtering->isChecked())
1118 std::map<int, Transform> posesFiltered;
1119 for(std::map<int, Transform>::const_iterator
iter=poses.begin();
iter!=poses.end(); ++
iter)
1121 bool ignore =
false;
1122 if(
_ui->doubleSpinBox_nodes_filtering_xmin->value() !=
_ui->doubleSpinBox_nodes_filtering_xmax->value() &&
1123 (
iter->second.x() <
_ui->doubleSpinBox_nodes_filtering_xmin->value() ||
1124 iter->second.x() >
_ui->doubleSpinBox_nodes_filtering_xmax->value()))
1128 if(
_ui->doubleSpinBox_nodes_filtering_ymin->value() !=
_ui->doubleSpinBox_nodes_filtering_ymax->value() &&
1129 (
iter->second.y() <
_ui->doubleSpinBox_nodes_filtering_ymin->value() ||
1130 iter->second.y() >
_ui->doubleSpinBox_nodes_filtering_ymax->value()))
1134 if(
_ui->doubleSpinBox_nodes_filtering_zmin->value() !=
_ui->doubleSpinBox_nodes_filtering_zmax->value() &&
1135 (
iter->second.z() <
_ui->doubleSpinBox_nodes_filtering_zmin->value() ||
1136 iter->second.z() >
_ui->doubleSpinBox_nodes_filtering_zmax->value()))
1142 posesFiltered.insert(*
iter);
1145 return posesFiltered;
1151 const std::map<int, Transform> & poses,
1152 const std::multimap<int, Link> & links,
1153 const std::map<int, int> & mapIds,
1154 const QMap<int, Signature> & cachedSignatures,
1155 const std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
1156 const std::map<int, LaserScan> & cachedScans,
1157 const QString & workingDirectory,
1160 std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
1161 std::map<int, pcl::PolygonMesh::Ptr> meshes;
1162 std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
1163 std::vector<std::map<int, pcl::PointXY> > textureVertexToPixels;
1179 textureVertexToPixels))
1181 if(textureMeshes.size())
1183 saveTextureMeshes(workingDirectory, poses, textureMeshes, cachedSignatures, textureVertexToPixels);
1185 else if(meshes.size())
1187 bool exportMeshes =
true;
1188 if(
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked())
1190 QMessageBox::StandardButton r = QMessageBox::warning(
this, tr(
"Exporting Texture Mesh"),
1191 tr(
"No texture mesh could be created, do you want to continue with saving only the meshes (%1)?").
arg(meshes.size()),
1192 QMessageBox::Yes|QMessageBox::No, QMessageBox::Yes);
1193 exportMeshes = r == QMessageBox::Yes;
1197 saveMeshes(workingDirectory, poses, meshes,
_ui->checkBox_binary->isChecked());
1202 saveClouds(workingDirectory, poses, clouds,
_ui->checkBox_binary->isChecked(), textureVertexToPixels);
1213 const std::map<int, Transform> & poses,
1214 const std::multimap<int, Link> & links,
1215 const std::map<int, int> & mapIds,
1216 const QMap<int, Signature> & cachedSignatures,
1217 const std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
1218 const std::map<int, LaserScan> & cachedScans,
1219 const QString & workingDirectory,
1222 std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
1223 std::map<int, pcl::PolygonMesh::Ptr> meshes;
1224 std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
1225 std::vector<std::map<int, pcl::PointXY> > textureVertexToPixels;
1241 textureVertexToPixels))
1243 QDialog * window =
new QDialog(this->parentWidget()?this->parentWidget():
this, Qt::Window);
1244 window->setAttribute(Qt::WA_DeleteOnClose,
true);
1247 window->setWindowTitle(tr(
"Meshes (%1 nodes)").
arg(meshes.size()));
1251 window->setWindowTitle(tr(
"Clouds (%1 nodes)").
arg(clouds.size()));
1253 window->setMinimumWidth(120);
1254 window->setMinimumHeight(90);
1255 window->resize(this->window()->windowHandle()->screen()->availableGeometry().
size() * 0.7);
1258 if(
_ui->comboBox_pipeline->currentIndex() == 0)
1265 if(
_ui->comboBox_intensityColormap->currentIndex()==1)
1269 else if(
_ui->comboBox_intensityColormap->currentIndex() == 2)
1274 QVBoxLayout *layout =
new QVBoxLayout();
1275 layout->addWidget(viewer);
1276 layout->setContentsMargins(0,0,0,0);
1277 window->setLayout(layout);
1278 connect(window, SIGNAL(finished(
int)), viewer, SLOT(clear()));
1283 QApplication::processEvents();
1285 QApplication::processEvents();
1287 if(textureMeshes.size())
1290 std::map<int, cv::Mat> images;
1291 std::map<int, std::vector<CameraModel> > calibrations;
1292 for(QMap<int, Signature>::const_iterator
iter=cachedSignatures.constBegin();
iter!=cachedSignatures.constEnd(); ++
iter)
1294 std::vector<CameraModel> models;
1295 if(
iter->sensorData().cameraModels().size())
1297 models =
iter->sensorData().cameraModels();
1299 else if(
iter->sensorData().stereoCameraModels().size())
1301 for(
size_t i=0;
i<
iter->sensorData().stereoCameraModels().
size(); ++
i)
1303 models.push_back(
iter->sensorData().stereoCameraModels()[
i].left());
1309 if(!
iter->sensorData().imageRaw().empty())
1311 calibrations.insert(std::make_pair(
iter.key(), models));
1312 images.insert(std::make_pair(
iter.key(),
iter->sensorData().imageRaw()));
1314 else if(!
iter->sensorData().imageCompressed().empty())
1316 calibrations.insert(std::make_pair(
iter.key(), models));
1317 images.insert(std::make_pair(
iter.key(),
iter->sensorData().imageCompressed()));
1321 int textureSize = 1024;
1322 if(
_ui->comboBox_meshingTextureSize->currentIndex() > 0)
1324 textureSize = 128 <<
_ui->comboBox_meshingTextureSize->currentIndex();
1326 int blendingDecimation = 0;
1327 if(
_ui->checkBox_blending->isChecked())
1329 if(
_ui->comboBox_blendingDecimation->currentIndex() > 0)
1331 blendingDecimation = 1 << (
_ui->comboBox_blendingDecimation->currentIndex()-1);
1335 for (std::map<int, pcl::TextureMesh::Ptr>::iterator
iter = textureMeshes.begin();
iter != textureMeshes.end(); ++
iter)
1337 pcl::TextureMesh::Ptr mesh =
iter->second;
1340 cv::Mat globalTexture;
1341 if (mesh->tex_materials.size() > 1)
1343 cv::Mat globalTextures;
1352 textureVertexToPixels,
1353 _ui->checkBox_gainCompensation->isChecked(),
1354 _ui->doubleSpinBox_gainBeta->value(),
1355 _ui->checkBox_gainRGB->isChecked(),
1356 _ui->checkBox_blending->isChecked(),
1358 _ui->spinBox_textureBrightnessContrastRatioLow->value(),
1359 _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
1360 _ui->checkBox_exposureFusion->isEnabled() &&
_ui->checkBox_exposureFusion->isChecked(),
1363 _ui->comboBox_texturingColorPolicy->currentIndex() == 1);
1364 if(globalTextures.rows == globalTextures.cols)
1366 globalTexture = globalTextures;
1373 bool hasColors =
false;
1374 for(
unsigned int i=0;
i<mesh->cloud.fields.size(); ++
i)
1376 if(mesh->cloud.fields[
i].name.compare(
"rgb") == 0)
1388 for (
unsigned int t = 0;
t < mesh->tex_coordinates.size(); ++
t)
1390 if(mesh->tex_polygons[
t].size())
1393 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr originalCloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1394 pcl::fromPCLPointCloud2(mesh->cloud, *originalCloud);
1397 unsigned int nPoints = mesh->tex_coordinates[
t].size();
1398 UASSERT(nPoints == mesh->tex_polygons[
t].size()*mesh->tex_polygons[
t][0].vertices.size());
1400 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1401 cloud->resize(nPoints);
1403 unsigned int oi = 0;
1404 size_t texCoordIndex = 0;
1405 for (
unsigned int i = 0;
i < mesh->tex_polygons[
t].size(); ++
i)
1407 pcl::Vertices &
vertices = mesh->tex_polygons[
t][
i];
1408 bool hasTexture =
true;
1409 for(
unsigned int j=0;
j<
vertices.vertices.size(); ++
j)
1411 if(mesh->tex_coordinates[
t][texCoordIndex][0] == -1 || mesh->tex_coordinates[
t][texCoordIndex][1] == -1)
1418 for(
unsigned int j=0;
j<
vertices.vertices.size(); ++
j)
1422 cloud->at(oi) = originalCloud->at(
vertices.vertices[
j]);
1423 if(hasTexture &&
_ui->comboBox_texturingColorPolicy->currentIndex() == 1) {
1424 cloud->at(oi).r = 255;
1425 cloud->at(oi).g = 255;
1426 cloud->at(oi).b = 255;
1432 texCoordIndex+=
vertices.vertices.size();
1434 pcl::toPCLPointCloud2(*cloud, mesh->cloud);
1438 UWARN(
"No polygons for texture %d of mesh %d?!",
t,
iter->first);
1444 for (
unsigned int t = 0;
t < mesh->tex_coordinates.size(); ++
t)
1446 if(mesh->tex_polygons[
t].size())
1449 pcl::PointCloud<pcl::PointNormal>::Ptr originalCloud(
new pcl::PointCloud<pcl::PointNormal>);
1450 pcl::fromPCLPointCloud2(mesh->cloud, *originalCloud);
1453 unsigned int nPoints = mesh->tex_coordinates[
t].size();
1454 UASSERT(nPoints == mesh->tex_polygons[
t].size()*mesh->tex_polygons[
t][0].vertices.size());
1456 pcl::PointCloud<pcl::PointNormal>::Ptr cloud(
new pcl::PointCloud<pcl::PointNormal>);
1457 cloud->resize(nPoints);
1459 unsigned int oi = 0;
1460 for (
unsigned int i = 0;
i < mesh->tex_polygons[
t].size(); ++
i)
1462 pcl::Vertices &
vertices = mesh->tex_polygons[
t][
i];
1464 for(
unsigned int j=0;
j<
vertices.vertices.size(); ++
j)
1468 cloud->at(oi) = originalCloud->at(
vertices.vertices[
j]);
1473 pcl::toPCLPointCloud2(*cloud, mesh->cloud);
1477 UWARN(
"No polygons for texture %d of mesh %d?!",
t,
iter->first);
1482 if (globalTexture.empty())
1484 if(mesh->tex_materials.size()==1 &&
1485 !mesh->tex_materials[0].tex_file.empty() &&
1486 uIsInteger(mesh->tex_materials[0].tex_file,
false))
1488 int textureId =
uStr2Int(mesh->tex_materials[0].tex_file);
1490 if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
1492 data = cachedSignatures.value(textureId).sensorData();
1499 data.uncompressDataConst(&globalTexture, 0);
1500 UASSERT(!globalTexture.empty());
1515 QApplication::processEvents();
1518 else if(meshes.size())
1521 viewer->
setLighting(
_ui->doubleSpinBox_transferColorRadius->value() < 0.0);
1522 for(std::map<int, pcl::PolygonMesh::Ptr>::iterator
iter = meshes.begin();
iter!=meshes.end(); ++
iter)
1527 for(
unsigned int i=0;
i<
iter->second->cloud.fields.size(); ++
i)
1529 if(
iter->second->cloud.fields[
i].name.compare(
"rgb") == 0)
1537 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
1538 pcl::fromPCLPointCloud2(
iter->second->cloud, *cloud);
1543 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZ>);
1544 pcl::fromPCLPointCloud2(
iter->second->cloud, *cloud);
1548 QApplication::processEvents();
1551 else if(clouds.size())
1553 for(std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::
iterator iter = clouds.begin();
iter!=clouds.end(); ++
iter)
1559 !(
_ui->checkBox_cameraProjection->isEnabled() &&
1560 _ui->checkBox_cameraProjection->isChecked() &&
1561 _ui->checkBox_camProjRecolorPoints->isChecked() &&
1562 clouds.size()==1 && clouds.begin()->first==0))
1565 if(
_ui->spinBox_normalKSearch->value()<=0 &&
_ui->doubleSpinBox_normalRadiusSearch->value()<=0.0)
1568 pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIWithoutNormals(
new pcl::PointCloud<pcl::PointXYZI>);
1569 cloudIWithoutNormals->resize(
iter->second->size());
1570 for(
unsigned int i=0;
i<cloudIWithoutNormals->size(); ++
i)
1572 cloudIWithoutNormals->points[
i].x =
iter->second->points[
i].x;
1573 cloudIWithoutNormals->points[
i].y =
iter->second->points[
i].y;
1574 cloudIWithoutNormals->points[
i].z =
iter->second->points[
i].z;
1575 int * intensity = (
int *)&cloudIWithoutNormals->points[
i].intensity;
1577 int(
iter->second->points[
i].r) |
1578 int(
iter->second->points[
i].g) << 8 |
1579 int(
iter->second->points[
i].b) << 16 |
1580 int(
iter->second->points[
i].a) << 24;
1586 pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloudI(
new pcl::PointCloud<pcl::PointXYZINormal>);
1587 cloudI->resize(
iter->second->size());
1588 for(
unsigned int i=0;
i<cloudI->size(); ++
i)
1590 cloudI->points[
i].x =
iter->second->points[
i].x;
1591 cloudI->points[
i].y =
iter->second->points[
i].y;
1592 cloudI->points[
i].z =
iter->second->points[
i].z;
1593 cloudI->points[
i].normal_x =
iter->second->points[
i].normal_x;
1594 cloudI->points[
i].normal_y =
iter->second->points[
i].normal_y;
1595 cloudI->points[
i].normal_z =
iter->second->points[
i].normal_z;
1596 cloudI->points[
i].curvature =
iter->second->points[
i].curvature;
1597 int * intensity = (
int *)&cloudI->points[
i].intensity;
1599 int(
iter->second->points[
i].r) |
1600 int(
iter->second->points[
i].g) << 8 |
1601 int(
iter->second->points[
i].b) << 16 |
1602 int(
iter->second->points[
i].a) << 24;
1617 window->activateWindow();
1628 int textureSize = 1024;
1629 if(
_ui->comboBox_meshingTextureSize->currentIndex() > 0)
1631 textureSize = 128 <<
_ui->comboBox_meshingTextureSize->currentIndex();
1637 return _ui->spinBox_mesh_maxTextures->value();
1641 return _ui->checkBox_gainCompensation->isChecked();
1645 return _ui->doubleSpinBox_gainBeta->value();
1649 return _ui->checkBox_gainRGB->isChecked();
1653 return _ui->checkBox_blending->isChecked();
1657 int blendingDecimation = 0;
1658 if(
_ui->checkBox_blending->isChecked())
1660 if(
_ui->comboBox_blendingDecimation->currentIndex() > 0)
1662 blendingDecimation = 1 << (
_ui->comboBox_blendingDecimation->currentIndex()-1);
1665 return blendingDecimation;
1669 return _ui->spinBox_textureBrightnessContrastRatioLow->value();
1673 return _ui->spinBox_textureBrightnessContrastRatioHigh->value();
1677 return _ui->checkBox_exposureFusion->isEnabled() &&
_ui->checkBox_exposureFusion->isChecked();
1685 if (dir.exists(dirName)) {
1686 Q_FOREACH(QFileInfo
info, dir.entryInfoList(QDir::NoDotAndDotDot | QDir::System | QDir::Hidden | QDir::AllDirs | QDir::Files, QDir::DirsFirst)) {
1691 result = QFile::remove(
info.absoluteFilePath());
1698 result = dir.rmdir(dirName);
1704 const std::map<int, Transform> & posesIn,
1705 const std::multimap<int, Link> & links,
1706 const std::map<int, int> & mapIds,
1707 const QMap<int, Signature> & cachedSignatures,
1708 const std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
1709 const std::map<int, LaserScan> & cachedScans,
1710 const QString & workingDirectory,
1712 std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & cloudsWithNormals,
1713 std::map<int, pcl::PolygonMesh::Ptr> & meshes,
1714 std::map<int, pcl::TextureMesh::Ptr> & textureMeshes,
1715 std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels)
1719 _ui->checkBox_regenerate->setEnabled(
true);
1720 if(cachedSignatures.empty() &&
_dbDriver)
1722 _ui->checkBox_regenerate->setChecked(
true);
1723 _ui->checkBox_regenerate->setEnabled(
false);
1730 if(this->
exec() == QDialog::Accepted)
1732 std::map<int, Transform> poses =
filterNodes(posesIn);
1736 QMessageBox::critical(
this, tr(
"Creating clouds..."), tr(
"Poses are empty! Cannot export/view clouds."));
1742 if(
_ui->checkBox_meshing->isChecked())
1746 if(
_ui->checkBox_assemble->isChecked())
1751 if(
_ui->checkBox_subtraction->isChecked())
1755 if(
_ui->checkBox_textureMapping->isChecked())
1759 if(
_ui->checkBox_gainCompensation->isChecked())
1763 if(
_ui->checkBox_mesh_quad->isEnabled())
1769 bool loadClouds =
true;
1770 #ifdef RTABMAP_OPENCHISEL
1771 if(
_ui->comboBox_meshingApproach->currentIndex()==4 &&
_ui->checkBox_assemble->isChecked())
1773 loadClouds = !
_ui->checkBox_fromDepth->isChecked();
1777 bool has2dScans =
false;
1778 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
1793 for(std::map<int, Transform>::const_iterator
iter=poses.begin();
iter!=poses.end(); ++
iter)
1795 clouds.insert(std::make_pair(
iter->first,
1797 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr(
new pcl::PointCloud<pcl::PointXYZRGBNormal>),
1798 pcl::IndicesPtr(
new std::vector<int>))));
1803 std::set<int> validCameras =
uKeysSet(clouds);
1814 if(
_ui->checkBox_regenerate->isEnabled() && !
_ui->checkBox_regenerate->isChecked())
1816 QMessageBox::warning(
this, tr(
"Creating clouds..."), tr(
"Could create clouds for %1 node(s). You "
1817 "may want to activate clouds regeneration option.").
arg(poses.size()));
1821 QMessageBox::warning(
this, tr(
"Creating clouds..."), tr(
"Could not create clouds for %1 "
1822 "node(s). The cache may not contain point cloud data. Try re-downloading the map.").
arg(poses.size()));
1828 if(
_ui->checkBox_gainCompensation->isChecked() &&
_ui->checkBox_fromDepth->isChecked() && clouds.size() > 1 &&
1830 !(
_ui->checkBox_meshing->isChecked() &&
1831 _ui->checkBox_textureMapping->isEnabled() &&
1832 _ui->checkBox_textureMapping->isChecked() &&
1833 _ui->comboBox_pipeline->currentIndex()==1 &&
1834 _ui->checkBox_assemble->isChecked() &&
1835 _ui->comboBox_meshingTextureSize->isEnabled() &&
1836 _ui->comboBox_meshingTextureSize->currentIndex() > 0) &&
1838 !(
_ui->comboBox_frame->isEnabled() &&
_ui->comboBox_frame->currentIndex()==2))
1843 if(
_ui->checkBox_gainFull->isChecked())
1851 QApplication::processEvents();
1853 QApplication::processEvents();
1855 if(
_ui->checkBox_gainFull->isChecked())
1857 std::multimap<int, Link> allLinks;
1858 for(std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator
iter=clouds.begin();
iter!=clouds.end(); ++
iter)
1860 int from =
iter->first;
1861 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator jter =
iter;
1863 for(;jter!=clouds.end(); ++jter)
1865 int to = jter->first;
1866 allLinks.insert(std::make_pair(from,
Link(from, to,
Link::kUserClosure, poses.at(from).inverse()*poses.at(to))));
1877 if(!(
_ui->checkBox_meshing->isChecked() &&
1878 _ui->checkBox_textureMapping->isEnabled() &&
1879 _ui->checkBox_textureMapping->isChecked()))
1882 for(std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::
iterator jter=clouds.begin();jter!=clouds.end(); ++jter)
1884 if(jter!=clouds.end())
1887 _compensator->
apply(jter->first, jter->second.first, jter->second.second,
_ui->checkBox_gainRGB->isChecked());
1891 QApplication::processEvents();
1902 std::map<int, Transform> normalViewpoints = poses;
1903 if(
_ui->checkBox_assemble->isChecked())
1906 for(std::map<int, Transform>::iterator
iter= normalViewpoints.begin();
iter!=normalViewpoints.end(); ++
iter)
1908 if(
_ui->checkBox_fromDepth->isChecked())
1910 std::vector<CameraModel> models;
1911 std::vector<StereoCameraModel> stereoModels;
1912 if(cachedSignatures.contains(
iter->first))
1915 models =
data.cameraModels();
1916 stereoModels =
data.stereoCameraModels();
1923 if(models.size() && !models[0].localTransform().isNull())
1925 iter->second *= models[0].localTransform();
1927 else if(stereoModels.size() && !stereoModels[0].localTransform().isNull())
1929 iter->second *= stereoModels[0].localTransform();
1936 iter->second *= cachedScans.at(
iter->first).localTransform();
1938 else if(cachedSignatures.contains(
iter->first))
1941 if(!
data.laserScanCompressed().isEmpty())
1943 iter->second *=
data.laserScanCompressed().localTransform();
1945 else if(!
data.laserScanRaw().isEmpty())
1947 iter->second *=
data.laserScanRaw().localTransform();
1961 pcl::PointCloud<pcl::PointXYZ>::Ptr rawAssembledCloud(
new pcl::PointCloud<pcl::PointXYZ>);
1962 std::vector<int> rawCameraIndices;
1963 if(
_ui->checkBox_assemble->isChecked() &&
1964 !((
_ui->comboBox_pipeline->currentIndex()==0 ||
_ui->comboBox_meshingApproach->currentIndex()==4) &&
_ui->checkBox_meshing->isChecked()))
1967 QApplication::processEvents();
1970 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr assembledCloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1971 for(std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::
iterator iter=clouds.begin();
1972 iter!= clouds.end();
1975 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformed(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1976 if(
iter->second.first->isOrganized())
1978 pcl::copyPointCloud(*
iter->second.first, *
iter->second.second, *transformed);
1985 pcl::copyPointCloud(*
iter->second.first, *
iter->second.second, *transformed);
1989 *assembledCloud += *transformed;
1990 rawCameraIndices.resize(assembledCloud->size(),
iter->first);
1994 QApplication::processEvents();
2001 assembledCloud->is_dense =
true;
2002 if(
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
2004 pcl::copyPointCloud(*assembledCloud, *rawAssembledCloud);
2007 if(
_ui->doubleSpinBox_voxelSize_assembled->value())
2010 .
arg(assembledCloud->size())
2011 .
arg(
_ui->doubleSpinBox_voxelSize_assembled->value()));
2012 QApplication::processEvents();
2013 unsigned int before = assembledCloud->size();
2016 _ui->doubleSpinBox_voxelSize_assembled->value());
2019 .
arg(
_ui->doubleSpinBox_voxelSize_assembled->value())
2020 .
arg(assembledCloud->size()));
2024 pcl::IndicesPtr
indices(
new std::vector<int>);
2025 indices->resize(assembledCloud->size());
2026 for(
unsigned int i=0;
i<
indices->size(); ++
i)
2031 if(!
_ui->checkBox_fromDepth->isChecked() && !has2dScans &&
2032 (
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0))
2035 .
arg(assembledCloud->size())
2036 .
arg(
_ui->spinBox_normalKSearch->value())
2037 .arg(
_ui->doubleSpinBox_normalRadiusSearch->value()));
2040 pcl::PointCloud<pcl::PointXYZ>::Ptr cloudWithoutNormals(
new pcl::PointCloud<pcl::PointXYZ>);
2041 pcl::copyPointCloud(*assembledCloud, *cloudWithoutNormals);
2042 pcl::PointCloud<pcl::Normal>::Ptr normals =
util3d::computeNormals(cloudWithoutNormals,
indices,
_ui->spinBox_normalKSearch->value(),
_ui->doubleSpinBox_normalRadiusSearch->value());
2044 UASSERT(assembledCloud->size() == normals->size());
2045 for(
unsigned int i=0;
i<normals->size(); ++
i)
2047 assembledCloud->points[
i].normal_x = normals->points[
i].normal_x;
2048 assembledCloud->points[
i].normal_y = normals->points[
i].normal_y;
2049 assembledCloud->points[
i].normal_z = normals->points[
i].normal_z;
2059 _ui->doubleSpinBox_groundNormalsUp->value());
2062 if(
_ui->spinBox_randomSamples_assembled->value()>0 &&
2063 (
int)assembledCloud->size() >
_ui->spinBox_randomSamples_assembled->value())
2066 .
arg(assembledCloud->size())
2067 .
arg(
_ui->spinBox_randomSamples_assembled->value()));
2070 .
arg(assembledCloud->size())
2071 .
arg(
_ui->spinBox_randomSamples_assembled->value()));
2074 clouds.insert(std::make_pair(0, std::make_pair(assembledCloud,
indices)));
2083 if(
_ui->checkBox_smoothing->isEnabled() &&
_ui->checkBox_smoothing->isChecked() && !has2dScans)
2086 "[search radius=%1m voxel=%2m]").
arg(
_ui->doubleSpinBox_mlsRadius->value()).
arg(
_ui->doubleSpinBox_voxelSize_assembled->value()));
2087 QApplication::processEvents();
2089 QApplication::processEvents();
2093 for(std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::
iterator iter=clouds.begin();
2094 iter!= clouds.end();)
2096 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudWithNormals =
iter->second.first;
2098 if(
_ui->checkBox_smoothing->isEnabled() &&
_ui->checkBox_smoothing->isChecked() && !has2dScans)
2100 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals(
new pcl::PointCloud<pcl::PointXYZRGB>);
2101 if(
iter->second.second->size())
2103 pcl::copyPointCloud(*cloudWithNormals, *
iter->second.second, *cloudWithoutNormals);
2107 pcl::copyPointCloud(*cloudWithNormals, *cloudWithoutNormals);
2111 QApplication::processEvents();
2113 QApplication::processEvents();
2120 cloudWithoutNormals,
2121 (
float)
_ui->doubleSpinBox_mlsRadius->value(),
2122 _ui->spinBox_polygonialOrder->value(),
2123 _ui->comboBox_upsamplingMethod->currentIndex(),
2124 (
float)
_ui->doubleSpinBox_sampleRadius->value(),
2125 (
float)
_ui->doubleSpinBox_sampleStep->value(),
2126 _ui->spinBox_randomPoints->value(),
2127 (
float)
_ui->doubleSpinBox_dilationVoxelSize->value(),
2128 _ui->spinBox_dilationSteps->value());
2131 UDEBUG(
"NaNs filtering... size before = %d", cloudWithNormals->size());
2133 UDEBUG(
"NaNs filtering... size after = %d", cloudWithNormals->size());
2135 if(
_ui->checkBox_assemble->isChecked())
2138 if(
_ui->doubleSpinBox_mls_outputVoxelSize->value())
2141 .
arg(cloudWithNormals->size())
2142 .
arg(
_ui->doubleSpinBox_mls_outputVoxelSize->value()));
2143 QApplication::processEvents();
2147 _ui->doubleSpinBox_mls_outputVoxelSize->value());
2159 else if(
iter->second.first->isOrganized() &&
_ui->checkBox_filtering->isChecked())
2164 cloudsWithNormals.insert(std::make_pair(
iter->first, cloudWithNormals));
2167 clouds.erase(
iter++);
2170 QApplication::processEvents();
2178 #ifdef RTABMAP_CPUTSDF
2179 cpu_tsdf::TSDFVolumeOctree::Ptr tsdf;
2181 #ifdef RTABMAP_OPENCHISEL
2182 chisel::ChiselPtr chiselMap;
2183 chisel::ProjectionIntegrator projectionIntegrator;
2187 std::map<int, std::vector<int> > organizedIndices;
2188 std::map<int, cv::Size> organizedCloudSizes;
2191 UDEBUG(
"Meshing=%d",
_ui->checkBox_meshing->isChecked()?1:0);
2192 if(
_ui->checkBox_meshing->isChecked() && !has2dScans)
2195 #ifdef RTABMAP_OPENCHISEL
2196 if(
_ui->comboBox_meshingApproach->currentIndex()==4 &&
_ui->checkBox_assemble->isChecked())
2200 QApplication::processEvents();
2202 QApplication::processEvents();
2204 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2205 std::vector<pcl::Vertices> mergedPolygons;
2207 int cloudsAdded = 1;
2208 for(std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::
iterator iter=cloudsWithNormals.begin();
2209 iter!= cloudsWithNormals.end();
2210 ++
iter,++cloudsAdded)
2212 std::vector<CameraModel> models;
2214 bool cacheHasCompressedImage =
false;
2216 if(cachedSignatures.contains(
iter->first))
2219 models =
data.cameraModels();
2220 cacheHasCompressedImage = !
data.imageCompressed().empty();
2221 scanInfo = !
data.laserScanRaw().isEmpty()?
data.laserScanRaw():
data.laserScanCompressed();
2229 if(chiselMap.get() == 0)
2232 int chunkSizeX =
_ui->spinBox_openchisel_chunk_size_x->value();
2233 int chunkSizeY =
_ui->spinBox_openchisel_chunk_size_y->value();
2234 int chunkSizeZ =
_ui->spinBox_openchisel_chunk_size_z->value();
2235 float voxelResolution =
_ui->doubleSpinBox_voxelSize_assembled->value();
2236 if(voxelResolution <=0.0
f)
2242 bool useColor =
_ui->checkBox_fromDepth->isChecked();
2243 chiselMap.reset(
new chisel::Chisel(Eigen::Vector3i(chunkSizeX, chunkSizeY, chunkSizeZ), voxelResolution, useColor));
2244 double truncationDistConst =
_ui->doubleSpinBox_openchisel_truncation_constant->value();
2245 double truncationDistLinear =
_ui->doubleSpinBox_openchisel_truncation_linear->value();
2246 double truncationDistQuad =
_ui->doubleSpinBox_openchisel_truncation_quadratic->value();
2247 double truncationDistScale =
_ui->doubleSpinBox_openchisel_truncation_scale->value();
2248 int weight =
_ui->spinBox_openchisel_integration_weight->value();
2249 bool useCarving =
_ui->checkBox_openchisel_use_voxel_carving->isChecked();
2250 double carvingDist =
_ui->doubleSpinBox_openchisel_carving_dist_m->value();
2251 chisel::Vec4 truncation(truncationDistQuad, truncationDistLinear, truncationDistConst, truncationDistScale);
2252 UDEBUG(
"If crashing just after this message, make sure PCL and OpenChisel are built both with -march=native or both without -march=native");
2253 projectionIntegrator.SetCentroids(chiselMap->GetChunkManager().GetCentroids());
2254 projectionIntegrator.SetTruncator(chisel::TruncatorPtr(
new chisel::QuadraticTruncator(truncation(0), truncation(1), truncation(2), truncation(3))));
2255 projectionIntegrator.SetWeighter(chisel::WeighterPtr(
new chisel::ConstantWeighter(weight)));
2256 projectionIntegrator.SetCarvingDist(carvingDist);
2257 projectionIntegrator.SetCarvingEnabled(useCarving);
2261 double nearPlaneDist =
_ui->doubleSpinBox_openchisel_near_plane_dist->value();
2262 double farPlaneDist =
_ui->doubleSpinBox_openchisel_far_plane_dist->value();
2263 if(
_ui->checkBox_fromDepth->isChecked())
2265 if(models.size() == 1 && !models[0].localTransform().isNull())
2270 if(cacheHasCompressedImage)
2272 cachedSignatures.find(
iter->first)->sensorData().uncompressDataConst(&rgb, &depth);
2278 data.uncompressDataConst(&rgb, &depth);
2280 if(!rgb.empty() && !depth.empty())
2284 if(rgb.cols > depth.cols)
2286 UASSERT(rgb.cols % depth.cols == 0);
2287 depthModel = depthModel.
scaled(
double(depth.cols)/
double(rgb.cols));
2290 if(depth.type() == CV_16UC1)
2295 std::shared_ptr<chisel::ColorImage<unsigned char> > colorChisel =
colorImageToChisel(rgb);
2300 cameraColor.SetNearPlane(nearPlaneDist);
2301 cameraColor.SetFarPlane(farPlaneDist);
2302 cameraDepth.SetNearPlane(nearPlaneDist);
2303 cameraDepth.SetFarPlane(farPlaneDist);
2305 chisel::Transform pose_rel_to_first_frame = (poses.at(
iter->first)*models[0].localTransform()).toEigen3f();
2306 chiselMap->IntegrateDepthScanColor<
float,
unsigned char>(projectionIntegrator, depthChisel, pose_rel_to_first_frame, cameraDepth, colorChisel, pose_rel_to_first_frame, cameraColor);
2324 chisel::Transform pose_rel_to_first_frame = (poses.at(
iter->first)*scanInfo.
localTransform()).toEigen3f();
2325 chiselMap->IntegratePointCloud(projectionIntegrator, *chiselCloud, pose_rel_to_first_frame, farPlaneDist);
2334 chiselMap->UpdateMeshes();
2339 QApplication::processEvents();
2349 if(
_ui->comboBox_pipeline->currentIndex() == 0)
2351 if(
_ui->comboBox_meshingApproach->currentIndex()==2)
2359 QApplication::processEvents();
2361 QApplication::processEvents();
2363 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2364 std::vector<pcl::Vertices> mergedPolygons;
2366 int cloudsAdded = 1;
2367 for(std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::
iterator iter=cloudsWithNormals.begin();
2368 iter!= cloudsWithNormals.end();
2369 ++
iter,++cloudsAdded)
2371 if(
iter->second->isOrganized())
2373 if(
iter->second->size())
2375 Eigen::Vector3f viewpoint(0.0
f,0.0
f,0.0
f);
2377 std::vector<CameraModel> models;
2378 std::vector<StereoCameraModel> stereoModels;
2379 if(cachedSignatures.contains(
iter->first))
2382 models =
data.cameraModels();
2383 stereoModels =
data.stereoCameraModels();
2390 #ifdef RTABMAP_CPUTSDF
2391 if(
_ui->comboBox_meshingApproach->currentIndex()==2 &&
_ui->checkBox_assemble->isChecked())
2395 if(models.size()==1 && models[0].isValidForProjection() && models[0].imageHeight()>0 && models[0].imageWidth()>0)
2397 float tsdf_size =
_ui->doubleSpinBox_cputsdf_size->value();
2398 float cell_size =
_ui->doubleSpinBox_cputsdf_resolution->value();
2399 int num_random_splits =
_ui->spinBox_cputsdf_randomSplit->value();
2401 int desired_res = tsdf_size / cell_size;
2404 while (desired_res >
n)
2410 tsdf.reset (
new cpu_tsdf::TSDFVolumeOctree);
2411 tsdf->setGridSize (tsdf_size, tsdf_size, tsdf_size);
2412 tsdf->setResolution (tsdf_res, tsdf_res, tsdf_res);
2413 float decimation =
float(models[0].imageWidth()) /
float(
iter->second->width);
2414 tsdf->setImageSize (models[0].imageWidth()/decimation, models[0].imageHeight()/decimation);
2415 tsdf->setCameraIntrinsics (models[0].
fx()/decimation, models[0].
fy()/decimation, models[0].
cx()/decimation, models[0].
cy()/decimation);
2416 tsdf->setNumRandomSplts (num_random_splits);
2417 tsdf->setSensorDistanceBounds (0, 9999);
2418 tsdf->setIntegrateColor(
true);
2419 tsdf->setDepthTruncationLimits (
_ui->doubleSpinBox_cputsdf_tuncPos->value(),
_ui->doubleSpinBox_cputsdf_tuncNeg->value());
2432 if(tsdf.get() && models.size() == 1 && !models[0].localTransform().isNull())
2434 Eigen::Affine3d pose_rel_to_first_frame = ((poses.begin()->second.inverse() * poses.at(
iter->first))*models[0].localTransform()).toEigen3d();
2435 if(!tsdf->integrateCloud(*
util3d::transformPointCloud(
iter->second, models[0].localTransform().inverse()), pcl::PointCloud<pcl::Normal>(), pose_rel_to_first_frame))
2437 _progressDialog->
appendText(tr(
"CPU-TSDF: Failed integrating cloud %1 (%2/%3) to TSDF volume").arg(
iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2441 _progressDialog->
appendText(tr(
"CPU-TSDF: Integrated cloud %1 (%2/%3) to TSDF volume").arg(
iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2449 if((
_ui->comboBox_frame->isEnabled() &&
_ui->comboBox_frame->currentIndex() != 2) ||
2450 !
iter->second->isOrganized())
2452 if(models.size() && !models[0].localTransform().isNull())
2454 viewpoint[0] = models[0].localTransform().x();
2455 viewpoint[1] = models[0].localTransform().y();
2456 viewpoint[2] = models[0].localTransform().z();
2458 else if(stereoModels.size() && !stereoModels[0].localTransform().isNull())
2460 viewpoint[0] = stereoModels[0].localTransform().x();
2461 viewpoint[1] = stereoModels[0].localTransform().y();
2462 viewpoint[2] = stereoModels[0].localTransform().z();
2468 _ui->doubleSpinBox_mesh_angleTolerance->value()*
M_PI/180.0,
2469 _ui->checkBox_mesh_quad->isEnabled() &&
_ui->checkBox_mesh_quad->isChecked(),
2470 _ui->spinBox_mesh_triangleSize->value(),
2473 if(
_ui->spinBox_mesh_minClusterSize->value() != 0)
2476 QApplication::processEvents();
2479 std::vector<std::set<int> > neighbors;
2480 std::vector<std::set<int> > vertexToPolygons;
2482 (
int)
iter->second->size(),
2487 _ui->spinBox_mesh_minClusterSize->value()<0?0:
_ui->spinBox_mesh_minClusterSize->value());
2489 std::vector<pcl::Vertices> filteredPolygons(polygons.size());
2490 if(
_ui->spinBox_mesh_minClusterSize->value() < 0)
2493 std::list<std::list<int> >
::iterator biggestClusterIndex = clusters.end();
2494 unsigned int biggestClusterSize = 0;
2497 if(
iter->size() > biggestClusterSize)
2499 biggestClusterIndex =
iter;
2500 biggestClusterSize =
iter->size();
2503 if(biggestClusterIndex != clusters.end())
2506 for(std::list<int>::iterator jter=biggestClusterIndex->begin(); jter!=biggestClusterIndex->end(); ++jter)
2508 filteredPolygons[oi++] = polygons.at(*jter);
2510 filteredPolygons.resize(oi);
2518 for(std::list<int>::iterator jter=
iter->begin(); jter!=
iter->end(); ++jter)
2520 filteredPolygons[oi++] = polygons.at(*jter);
2523 filteredPolygons.resize(oi);
2525 int before = (
int)polygons.size();
2526 polygons = filteredPolygons;
2528 if(polygons.size() == 0)
2530 std::string
msg =
uFormat(
"All %d polygons filtered after polygon cluster filtering. Cluster minimum size is %d.", before,
_ui->spinBox_mesh_minClusterSize->value());
2536 QApplication::processEvents();
2541 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr denseCloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2542 std::vector<pcl::Vertices> densePolygons;
2545 if(!
_ui->checkBox_assemble->isChecked() ||
2546 (
_ui->checkBox_textureMapping->isEnabled() &&
2547 _ui->checkBox_textureMapping->isChecked() &&
2548 _ui->doubleSpinBox_voxelSize_assembled->value() == 0.0))
2550 if(
_ui->checkBox_assemble->isChecked())
2555 pcl::PolygonMesh::Ptr mesh(
new pcl::PolygonMesh);
2556 pcl::toPCLPointCloud2(*denseCloud, mesh->cloud);
2557 mesh->polygons = densePolygons;
2559 organizedIndices.insert(std::make_pair(
iter->first, denseToOrganizedIndices));
2560 organizedCloudSizes.insert(std::make_pair(
iter->first, cv::Size(
iter->second->width,
iter->second->height)));
2562 meshes.insert(std::make_pair(
iter->first, mesh));
2567 if(mergedClouds->size() == 0)
2569 *mergedClouds = *denseCloud;
2570 mergedPolygons = densePolygons;
2587 if(cachedSignatures.contains(
iter->first))
2589 const Signature &
s = cachedSignatures.find(
iter->first).value();
2590 weight =
s.getWeight();
2598 _progressDialog->
appendText(tr(
"Mesh %1 not created (cloud is not organized). You may want to check cloud regeneration option (%2/%3).").
arg(
iter->first).
arg(cloudsAdded).arg(cloudsWithNormals.size()));
2603 QApplication::processEvents();
2610 if(
_ui->checkBox_assemble->isChecked() && mergedClouds->size())
2612 if(
_ui->doubleSpinBox_voxelSize_assembled->value())
2614 _progressDialog->
appendText(tr(
"Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").
arg(mergedClouds->size()).
arg(mergedPolygons.size()));
2615 QApplication::processEvents();
2620 _ui->doubleSpinBox_voxelSize_assembled->value(),
2625 unsigned int count = mergedPolygons.size();
2628 QApplication::processEvents();
2631 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2632 std::vector<pcl::Vertices> filteredPolygons;
2634 mergedClouds = filteredCloud;
2635 mergedPolygons = filteredPolygons;
2638 pcl::PolygonMesh::Ptr mesh(
new pcl::PolygonMesh);
2639 pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
2640 mesh->polygons = mergedPolygons;
2642 meshes.insert(std::make_pair(0, mesh));
2645 QApplication::processEvents();
2650 if(
_ui->comboBox_meshingApproach->currentIndex() == 0)
2658 QApplication::processEvents();
2660 QApplication::processEvents();
2663 for(std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::
iterator iter=cloudsWithNormals.begin();
2664 iter!= cloudsWithNormals.end();
2665 ++
iter,++cloudsAdded)
2667 pcl::PolygonMesh::Ptr mesh(
new pcl::PolygonMesh);
2668 if(
_ui->comboBox_meshingApproach->currentIndex() == 0)
2672 _ui->doubleSpinBox_gp3Radius->value(),
2673 _ui->doubleSpinBox_gp3Mu->value());
2677 pcl::Poisson<pcl::PointXYZRGBNormal> poisson;
2678 poisson.setOutputPolygons(
_ui->checkBox_poisson_outputPolygons->isEnabled()?
_ui->checkBox_poisson_outputPolygons->isChecked():
false);
2679 poisson.setManifold(
_ui->checkBox_poisson_manifold->isChecked());
2680 poisson.setSamplesPerNode(
_ui->doubleSpinBox_poisson_samples->value());
2681 int depth =
_ui->spinBox_poisson_depth->value();
2688 for(
int i=6;
i<12; ++
i)
2690 if(mapLength/
float(1<<
i) <
_ui->doubleSpinBox_poisson_targetPolygonSize->value())
2701 QApplication::processEvents();
2703 QApplication::processEvents();
2705 poisson.setDepth(depth);
2706 poisson.setIsoDivide(
_ui->spinBox_poisson_iso->value());
2707 poisson.setSolverDivide(
_ui->spinBox_poisson_solver->value());
2708 poisson.setMinDepth(
_ui->spinBox_poisson_minDepth->value());
2709 poisson.setPointWeight(
_ui->doubleSpinBox_poisson_pointWeight->value());
2710 poisson.setScale(
_ui->doubleSpinBox_poisson_scale->value());
2711 poisson.setInputCloud(
iter->second);
2712 poisson.reconstruct(*mesh);
2716 QApplication::processEvents();
2718 if(mesh->polygons.size()>0)
2725 int maxIntensity = 1;
2727 for(
size_t i=0;
i<
iter->second->size(); ++
i)
2731 int(
iter->second->points[
i].g) << 8 |
2732 int(
iter->second->points[
i].b) << 16 |
2733 int(
iter->second->points[
i].a) << 24;
2734 if(intensity > maxIntensity)
2736 maxIntensity = intensity;
2740 for(
size_t i=0;
i<
iter->second->size(); ++
i)
2744 int(
iter->second->points[
i].g) << 8 |
2745 int(
iter->second->points[
i].b) << 16 |
2746 int(
iter->second->points[
i].a) << 24;
2747 intensity = intensity*255/maxIntensity;
2748 iter->second->points[
i].r = (
unsigned char)intensity;
2749 iter->second->points[
i].g = (
unsigned char)intensity;
2750 iter->second->points[
i].b = (
unsigned char)intensity;
2751 iter->second->points[
i].a = (
unsigned char)255;
2755 util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
2757 _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(
float)
_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
2758 _ui->spinBox_meshMaxPolygons->isEnabled()?
_ui->spinBox_meshMaxPolygons->value():0,
2760 (
float)
_ui->doubleSpinBox_transferColorRadius->value(),
2761 !(
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked() &&
_ui->comboBox_texturingColorPolicy->currentIndex()==0),
2762 _ui->checkBox_cleanMesh->isChecked(),
2763 _ui->spinBox_mesh_minClusterSize->value(),
2765 meshes.insert(std::make_pair(
iter->first, mesh));
2774 QApplication::processEvents();
2782 else if(
_ui->checkBox_meshing->isChecked())
2784 std::string
msg =
uFormat(
"Some clouds are 2D laser scans. Meshing can be done only from RGB-D clouds or 3D laser scans.");
2788 else if(
_ui->checkBox_cameraProjection->isEnabled() &&
2789 _ui->checkBox_cameraProjection->isChecked() &&
2790 cloudsWithNormals.size()==1 && cloudsWithNormals.begin()->first==0)
2793 QApplication::processEvents();
2795 QApplication::processEvents();
2797 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr assembledCloud = cloudsWithNormals.begin()->second;
2800 std::map<int, std::vector<CameraModel> > cameraModels;
2801 for(std::map<int, Transform>::const_iterator
iter=poses.lower_bound(0);
iter!=poses.end(); ++
iter)
2803 std::vector<CameraModel> models;
2804 std::vector<StereoCameraModel> stereoModels;
2805 if(cachedSignatures.contains(
iter->first))
2808 models =
data.cameraModels();
2809 stereoModels =
data.stereoCameraModels();
2816 if(stereoModels.size())
2819 for(
size_t i=0;
i<stereoModels.size(); ++
i)
2821 models.push_back(stereoModels[
i].left());
2825 if(models.size() == 0 || !models[0].isValidForProjection())
2830 if(!models.empty() && models[0].imageWidth() != 0 && models[0].imageHeight() != 0)
2833 cameraModels.insert(std::make_pair(
iter->first, models));
2837 UWARN(
"%d node has invalid camera models, ignoring it.",
iter->first);
2844 std::vector<float> roiRatios;
2845 QStringList strings =
_ui->lineEdit_camProjRoiRatios->text().split(
' ');
2846 if(!
_ui->lineEdit_meshingTextureRoiRatios->text().isEmpty())
2848 if(strings.size()==4)
2850 roiRatios.resize(4);
2851 roiRatios[0]=strings[0].toDouble();
2852 roiRatios[1]=strings[1].toDouble();
2853 roiRatios[2]=strings[2].toDouble();
2854 roiRatios[3]=strings[3].toDouble();
2855 if(!(roiRatios[0]>=0.0
f && roiRatios[0]<=1.0
f &&
2856 roiRatios[1]>=0.0
f && roiRatios[1]<=1.0
f &&
2857 roiRatios[2]>=0.0
f && roiRatios[2]<=1.0
f &&
2858 roiRatios[3]>=0.0
f && roiRatios[3]<=1.0
f))
2863 if(roiRatios.empty())
2865 QString
msg = tr(
"Wrong ROI format. Region of Interest (ROI) must "
2866 "have 4 values [left right top bottom] between 0 and 1 "
2867 "separated by space (%1), ignoring it for projecting cameras...")
2868 .arg(
_ui->lineEdit_camProjRoiRatios->text());
2875 std::map<int, std::vector<rtabmap::CameraModel> > cameraModelsProj;
2876 if(
_ui->spinBox_camProjDecimation->value()>1)
2878 for(std::map<
int, std::vector<rtabmap::CameraModel> >::
iterator iter=cameraModels.begin();
2879 iter!=cameraModels.end();
2882 std::vector<rtabmap::CameraModel> models;
2883 for(
size_t i=0;
i<
iter->second.size(); ++
i)
2885 models.push_back(
iter->second[
i].scaled(1.0/
double(
_ui->spinBox_camProjDecimation->value())));
2887 cameraModelsProj.insert(std::make_pair(
iter->first, models));
2892 cameraModelsProj = cameraModels;
2896 if(!
_ui->lineEdit_camProjMaskFilePath->text().isEmpty())
2898 projMask = cv::imread(
_ui->lineEdit_camProjMaskFilePath->text().toStdString(), cv::IMREAD_GRAYSCALE);
2899 if(
_ui->spinBox_camProjDecimation->value()>1)
2901 cv::Mat
out = projMask;
2902 cv::resize(projMask,
out, cv::Size(), 1.0
f/
float(
_ui->spinBox_camProjDecimation->value()), 1.0f/
float(
_ui->spinBox_camProjDecimation->value()), cv::INTER_NEAREST);
2907 std::vector<std::pair< std::pair<int, int>, pcl::PointXY> > pointToPixel;
2912 _ui->doubleSpinBox_camProjMaxDistance->value(),
2913 _ui->doubleSpinBox_camProjMaxAngle->value()*
M_PI/180.0,
2916 _ui->checkBox_camProjDistanceToCamPolicy->isChecked(),
2925 UASSERT(pointToPixel.empty() || pointToPixel.size() == assembledCloud->size());
2926 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr assembledCloudValidPoints;
2927 if(!
_ui->checkBox_camProjKeepPointsNotSeenByCameras->isChecked())
2929 assembledCloudValidPoints.reset(
new pcl::PointCloud<pcl::PointXYZRGBNormal>());
2930 assembledCloudValidPoints->resize(assembledCloud->size());
2932 if(
_ui->comboBox_camProjExportCamera->isEnabled() &&
2933 _ui->comboBox_camProjExportCamera->currentIndex()>0)
2935 textureVertexToPixels.resize(assembledCloud->size());
2938 if(
_ui->checkBox_camProjRecolorPoints->isChecked())
2943 int nodeID =
iter->first;
2946 if(cachedSignatures.contains(nodeID) && !cachedSignatures.value(nodeID).sensorData().imageCompressed().empty())
2948 cachedSignatures.value(nodeID).sensorData().uncompressDataConst(&image, 0);
2954 data.uncompressDataConst(&image, 0);
2959 if(
_ui->spinBox_camProjDecimation->value()>1)
2964 UASSERT(cameraModelsProj.find(nodeID) != cameraModelsProj.end());
2965 int modelsSize = cameraModelsProj.at(nodeID).size();
2966 for(
size_t i=0;
i<pointToPixel.size(); ++
i)
2968 int cameraIndex = pointToPixel[
i].first.second;
2969 if(nodeID == pointToPixel[
i].
first.first && cameraIndex>=0)
2971 int subImageWidth = image.cols / modelsSize;
2972 cv::Mat subImage = image(
cv::Range::all(), cv::Range(cameraIndex*subImageWidth, (cameraIndex+1)*subImageWidth));
2974 int x = pointToPixel[
i].second.x * (
float)subImage.cols;
2975 int y = pointToPixel[
i].second.y * (
float)subImage.rows;
2979 pcl::PointXYZRGBNormal & pt = assembledCloud->at(
i);
2980 if(subImage.type()==CV_8UC3)
2982 cv::Vec3b bgr = subImage.at<cv::Vec3b>(
y,
x);
2989 UASSERT(subImage.type()==CV_8UC1);
2990 pt.r = pt.g = pt.b = subImage.at<
unsigned char>(pointToPixel[
i].second.y * subImage.rows, pointToPixel[
i].second.x * subImage.cols);
2995 QString
msg = tr(
"Processed %1/%2 images").arg(imagesDone++).arg(
cameraPoses.size());
2998 QApplication::processEvents();
3002 pcl::IndicesPtr validIndices(
new std::vector<int>(pointToPixel.size()));
3004 for(
size_t i=0;
i<pointToPixel.size() && !
_canceled; ++
i)
3006 pcl::PointXYZRGBNormal & pt = assembledCloud->at(
i);
3007 if(pointToPixel[
i].
first.first <=0)
3009 if(
_ui->checkBox_camProjRecolorPoints->isChecked() && !
_ui->checkBox_fromDepth->isChecked() && !
_scansHaveRGB)
3019 int nodeID = pointToPixel[
i].first.first;
3020 int cameraIndex = pointToPixel[
i].first.second;
3021 int exportedId = nodeID;
3022 if(
_ui->comboBox_camProjExportCamera->currentIndex() == 2)
3024 exportedId = cameraIndex+1;
3026 else if(
_ui->comboBox_camProjExportCamera->currentIndex() == 3)
3028 UASSERT_MSG(cameraIndex<10,
"Exporting cam id as NodeId+CamIndex is only supported when the number of cameras per node < 10.");
3029 exportedId = nodeID*10 + cameraIndex;
3032 if(assembledCloudValidPoints.get())
3034 if(!textureVertexToPixels.empty())
3036 textureVertexToPixels[oi].insert(std::make_pair(exportedId, pointToPixel[
i].
second));
3038 assembledCloudValidPoints->at(oi++) = pt;
3040 else if(!textureVertexToPixels.empty())
3042 textureVertexToPixels[
i].insert(std::make_pair(exportedId, pointToPixel[
i].
second));
3047 if(assembledCloudValidPoints.get())
3049 assembledCloudValidPoints->resize(oi);
3050 cloudsWithNormals.begin()->second = assembledCloudValidPoints;
3052 if(!textureVertexToPixels.empty())
3054 textureVertexToPixels.resize(oi);
3066 #ifdef RTABMAP_CPUTSDF
3070 QApplication::processEvents();
3072 QApplication::processEvents();
3074 cpu_tsdf::MarchingCubesTSDFOctree mc;
3075 mc.setMinWeight (
_ui->doubleSpinBox_cputsdf_minWeight->value());
3076 mc.setInputTSDF (tsdf);
3077 mc.setColorByRGB (
true);
3078 pcl::PolygonMesh::Ptr mesh (
new pcl::PolygonMesh);
3079 mc.reconstruct (*mesh);
3083 if(mesh->polygons.size()>0)
3086 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr
vertices (
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
3087 pcl::fromPCLPointCloud2 (mesh->cloud, *
vertices);
3089 if(
_ui->doubleSpinBox_cputsdf_flattenRadius->value()>0.0)
3092 QApplication::processEvents();
3094 QApplication::processEvents();
3096 float min_dist =
_ui->doubleSpinBox_cputsdf_flattenRadius->value();
3097 pcl::search::KdTree<pcl::PointXYZRGBNormal> vert_tree (
true);
3098 vert_tree.setInputCloud (
vertices);
3100 std::vector<int> vertex_remap (
vertices->size (), -1);
3102 std::vector<int> neighbors;
3103 std::vector<float> dists;
3104 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr vertices_new(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
3105 vertices_new->resize(
vertices->size ());
3108 if (vertex_remap[
i] >= 0)
3110 vertex_remap[
i] = idx;
3111 vert_tree.radiusSearch (
i, min_dist, neighbors, dists);
3112 for (
size_t j = 1;
j < neighbors.size ();
j++)
3114 if (dists[
j] < min_dist)
3115 vertex_remap[neighbors[
j]] = idx;
3117 vertices_new->at(idx++) =
vertices->at (
i);
3119 vertices_new->resize(idx);
3120 std::vector<size_t> faces_to_remove;
3121 size_t face_idx = 0;
3122 for (
size_t i = 0;
i < mesh->polygons.size ();
i++)
3124 pcl::Vertices &
v = mesh->polygons[
i];
3125 for (
size_t j = 0;
j <
v.vertices.size ();
j++)
3127 v.vertices[
j] = vertex_remap[
v.vertices[
j]];
3129 if (!(
v.vertices[0] ==
v.vertices[1] ||
v.vertices[1] ==
v.vertices[2] ||
v.vertices[2] ==
v.vertices[0]))
3131 mesh->polygons[face_idx++] = mesh->polygons[
i];
3134 mesh->polygons.resize (face_idx);
3135 pcl::toPCLPointCloud2 (*vertices_new, mesh->cloud);
3139 pcl::fromPCLPointCloud2(mesh->cloud, *
vertices);
3141 util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
3143 _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(
float)
_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
3144 _ui->spinBox_meshMaxPolygons->isEnabled()?
_ui->spinBox_meshMaxPolygons->value():0,
3146 (
float)
_ui->doubleSpinBox_transferColorRadius->value(),
3147 !(
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked() &&
_ui->comboBox_texturingColorPolicy->currentIndex()==0),
3148 _ui->checkBox_cleanMesh->isChecked(),
3149 _ui->spinBox_mesh_minClusterSize->value(),
3151 meshes.insert(std::make_pair(0, mesh));
3160 #ifdef RTABMAP_OPENCHISEL
3164 QApplication::processEvents();
3166 QApplication::processEvents();
3168 const chisel::MeshMap& meshMap = chiselMap->GetChunkManager().GetAllMeshes();
3179 if(mesh->polygons.size()>0)
3181 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
3182 pcl::fromPCLPointCloud2(mesh->cloud, *mergedClouds);
3183 if(
_ui->checkBox_openchisel_mergeVertices->isChecked())
3185 _progressDialog->
appendText(tr(
"Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").
arg(mergedClouds->size()).
arg(mesh->polygons.size()));
3186 QApplication::processEvents();
3191 _ui->doubleSpinBox_voxelSize_assembled->value()/2.0,
3196 unsigned int count = mesh->polygons.size();
3199 QApplication::processEvents();
3202 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
3203 std::vector<pcl::Vertices> filteredPolygons;
3204 count = mergedClouds->size();
3206 mergedClouds = filteredCloud;
3207 pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
3208 mesh->polygons = filteredPolygons;
3210 QApplication::processEvents();
3213 util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
3215 _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(
float)
_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
3216 _ui->spinBox_meshMaxPolygons->isEnabled()?
_ui->spinBox_meshMaxPolygons->value():0,
3218 (
float)
_ui->doubleSpinBox_transferColorRadius->value(),
3219 !(
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked() &&
_ui->comboBox_texturingColorPolicy->currentIndex()==0),
3220 _ui->checkBox_cleanMesh->isChecked(),
3221 _ui->spinBox_mesh_minClusterSize->value(),
3223 meshes.insert(std::make_pair(0, mesh));
3240 UDEBUG(
"texture mapping=%d",
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked()?1:0);
3241 if(!has2dScans && !meshes.empty() &&
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked())
3244 QApplication::processEvents();
3246 QApplication::processEvents();
3249 for(std::map<int, pcl::PolygonMesh::Ptr>::iterator
iter=meshes.begin();
3250 iter!= meshes.end();
3253 std::map<int, Transform>
cameras;
3254 if(
iter->first == 0)
3264 std::map<int, std::vector<CameraModel> > cameraModels;
3265 std::map<int, cv::Mat > cameraDepths;
3266 int ignoredCameras = 0;
3267 for(std::map<int, Transform>::iterator jter=
cameras.begin(); jter!=
cameras.end(); ++jter)
3269 if(validCameras.find(jter->first) != validCameras.end())
3271 std::vector<CameraModel> models;
3272 std::vector<StereoCameraModel> stereoModels;
3273 bool cacheHasCompressedImage =
false;
3274 if(cachedSignatures.contains(jter->first))
3276 const SensorData &
data = cachedSignatures.find(jter->first)->sensorData();
3277 models =
data.cameraModels();
3278 stereoModels =
data.stereoCameraModels();
3279 cacheHasCompressedImage = !
data.imageCompressed().empty();
3287 if(stereoModels.size())
3291 for(
size_t i=0;
i<stereoModels.size(); ++
i)
3293 models.push_back(stereoModels[
i].left());
3297 if(models.size() == 0 || !models[0].isValidForProjection())
3302 if(!jter->second.isNull() && models.size())
3305 bool blurryImage =
false;
3306 bool getDepth = !stereo &&
_ui->doubleSpinBox_meshingTextureMaxDepthError->value() >= 0.0f;
3309 if(models[0].imageWidth() == 0 || models[0].imageHeight() == 0)
3313 if(cacheHasCompressedImage)
3315 cachedSignatures.find(jter->first)->sensorData().uncompressDataConst(&
img,
getDepth?&depth:0);
3316 velocity = cachedSignatures.find(jter->first)->getVelocity();
3324 if(
_ui->checkBox_cameraFilter->isChecked() &&
3325 (
_ui->doubleSpinBox_cameraFilterVel->value()>0.0 ||
_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
3336 cv::Size imageSize =
img.size();
3337 imageSize.width /= models.size();
3338 for(
unsigned int i=0;
i<models.size(); ++
i)
3340 models[
i].setImageSize(imageSize);
3345 bool getImg =
_ui->checkBox_cameraFilter->isChecked() &&
_ui->doubleSpinBox_laplacianVariance->value()>0.0;
3347 if(cacheHasCompressedImage)
3349 cachedSignatures.find(jter->first)->sensorData().uncompressDataConst(getImg?&
img:0,
getDepth?&depth:0);
3350 velocity = cachedSignatures.find(jter->first)->getVelocity();
3358 if(
_ui->checkBox_cameraFilter->isChecked() &&
3359 (
_ui->doubleSpinBox_cameraFilterVel->value()>0.0 ||
_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
3371 if(
_ui->checkBox_cameraFilter->isChecked())
3375 (
_ui->doubleSpinBox_cameraFilterVel->value()>0.0 ||
_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
3381 if(
_ui->doubleSpinBox_cameraFilterVel->value()>0.0 && transVel >
_ui->doubleSpinBox_cameraFilterVel->value())
3383 msg =
uFormat(
"Fast motion detected for camera %d (speed=%f m/s > thr=%f m/s), camera is ignored for texturing.", jter->first, transVel,
_ui->doubleSpinBox_cameraFilterVel->value());
3386 else if(
_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0 && rotVel >
_ui->doubleSpinBox_cameraFilterVelRad->value())
3388 msg =
uFormat(
"Fast motion detected for camera %d (speed=%f rad/s > thr=%f rad/s), camera is ignored for texturing.", jter->first, rotVel,
_ui->doubleSpinBox_cameraFilterVelRad->value());
3394 UWARN(
"Camera motion filtering is set, but velocity of camera %d is not available.", jter->first);
3398 if(!blurryImage && !
img.empty() &&
_ui->doubleSpinBox_laplacianVariance->value()>0.0)
3400 cv::Mat imgLaplacian;
3401 cv::Laplacian(
img, imgLaplacian, CV_16S);
3403 cv::meanStdDev(imgLaplacian,
m,
s);
3404 double stddev_pxl =
s.at<
double>(0);
3405 double var = stddev_pxl*stddev_pxl;
3406 if(var < _ui->doubleSpinBox_laplacianVariance->value())
3409 msg =
uFormat(
"Camera's image %d is detected as blurry (var=%f, thr=%f), camera is ignored for texturing.", jter->first, var,
_ui->doubleSpinBox_laplacianVariance->value());
3415 QApplication::processEvents();
3420 if(!blurryImage && models[0].imageWidth() != 0 && models[0].imageHeight() != 0)
3422 cameraPoses.insert(std::make_pair(jter->first, jter->second));
3423 cameraModels.insert(std::make_pair(jter->first, models));
3426 cameraDepths.insert(std::make_pair(jter->first, depth));
3432 if(ignoredCameras > (
int)validCameras.size()/2)
3434 std::string
msg =
uFormat(
"More than 50%% of the cameras (%d/%d) have been filtered for "
3435 "too fast motion and/or blur level. You may adjust the corresponding thresholds.",
3436 ignoredCameras, (
int)validCameras.size());
3440 QApplication::processEvents();
3445 pcl::TextureMesh::Ptr textureMesh(
new pcl::TextureMesh);
3446 std::map<int, std::vector<int> >
::iterator oter = organizedIndices.find(
iter->first);
3447 std::map<int, cv::Size>::iterator ster = organizedCloudSizes.find(
iter->first);
3448 if(
iter->first != 0 && oter != organizedIndices.end())
3450 UASSERT(ster!=organizedCloudSizes.end()&&ster->first == oter->first);
3451 UDEBUG(
"Texture by pixels");
3452 textureMesh->cloud =
iter->second->cloud;
3453 textureMesh->tex_polygons.push_back(
iter->second->polygons);
3454 int w = ster->second.width;
3455 int h = ster->second.height;
3457 if(textureMesh->tex_polygons.size() && textureMesh->tex_polygons[0].size())
3459 textureMesh->tex_coordinates.resize(1);
3462 int polygonSize = (
int)textureMesh->tex_polygons[0][0].vertices.size();
3463 textureMesh->tex_coordinates[0].resize(polygonSize*textureMesh->tex_polygons[0].size());
3464 for(
unsigned int i=0;
i<textureMesh->tex_polygons[0].size(); ++
i)
3466 const pcl::Vertices &
vertices = textureMesh->tex_polygons[0][
i];
3468 for(
int k=0; k<polygonSize; ++k)
3472 int originalVertex = oter->second[
vertices.vertices[k]];
3473 textureMesh->tex_coordinates[0][
i*polygonSize+k] = Eigen::Vector2f(
3474 float(originalVertex %
w) /
float(
w),
3475 float(
h - originalVertex /
w) /
float(
h));
3479 pcl::TexMaterial mesh_material;
3480 mesh_material.tex_d = 1.0f;
3481 mesh_material.tex_Ns = 75.0f;
3482 mesh_material.tex_illum = 1;
3484 std::stringstream tex_name;
3485 tex_name <<
"material_" <<
iter->first;
3486 tex_name >> mesh_material.tex_name;
3488 mesh_material.tex_file =
uFormat(
"%d",
iter->first);
3489 textureMesh->tex_materials.push_back(mesh_material);
3493 UWARN(
"No polygons for mesh %d!?",
iter->first);
3498 UDEBUG(
"Texture by projection");
3500 if(
cameraPoses.size() &&
_ui->checkBox_cameraFilter->isChecked())
3504 _ui->doubleSpinBox_cameraFilterRadius->value(),
3505 _ui->doubleSpinBox_cameraFilterAngle->value());
3506 for(std::map<
int, std::vector<CameraModel> >::
iterator modelIter = cameraModels.begin(); modelIter!=cameraModels.end();)
3510 cameraModels.erase(modelIter++);
3511 cameraDepths.erase(modelIter->first);
3519 QApplication::processEvents();
3521 QApplication::processEvents();
3531 if(cameraModels.size() && cameraModels.begin()->second.size()>1)
3536 std::vector<float> roiRatios;
3537 QStringList strings =
_ui->lineEdit_meshingTextureRoiRatios->text().split(
' ');
3538 if(!
_ui->lineEdit_meshingTextureRoiRatios->text().isEmpty())
3540 if(strings.size()==4)
3542 roiRatios.resize(4);
3543 roiRatios[0]=strings[0].toDouble();
3544 roiRatios[1]=strings[1].toDouble();
3545 roiRatios[2]=strings[2].toDouble();
3546 roiRatios[3]=strings[3].toDouble();
3547 if(!(roiRatios[0]>=0.0
f && roiRatios[0]<=1.0
f &&
3548 roiRatios[1]>=0.0
f && roiRatios[1]<=1.0
f &&
3549 roiRatios[2]>=0.0
f && roiRatios[2]<=1.0
f &&
3550 roiRatios[3]>=0.0
f && roiRatios[3]<=1.0
f))
3555 if(roiRatios.empty())
3557 QString
msg = tr(
"Wrong ROI format. Region of Interest (ROI) must have 4 "
3558 "values [left right top bottom] between 0 and 1 "
3559 "separated by space (%1), ignoring it for texturing...")
3560 .arg(
_ui->lineEdit_meshingTextureRoiRatios->text());
3572 _ui->doubleSpinBox_meshingTextureMaxDistance->value(),
3573 _ui->doubleSpinBox_meshingTextureMaxDepthError->value(),
3574 _ui->doubleSpinBox_meshingTextureMaxAngle->value()*
M_PI/180.0,
3575 _ui->spinBox_mesh_minTextureClusterSize->value(),
3579 _ui->checkBox_distanceToCamPolicy->isChecked());
3587 if(
_ui->checkBox_cleanMesh->isChecked())
3589 unsigned int totalSize = 0;
3590 for(
unsigned int t=0;
t<textureMesh->tex_polygons.size(); ++
t)
3592 totalSize+=textureMesh->tex_polygons[
t].size();
3597 unsigned int totalSizeAfter = 0;
3598 for(
unsigned int t=0;
t<textureMesh->tex_polygons.size(); ++
t)
3600 totalSizeAfter+=textureMesh->tex_polygons[
t].size();
3606 textureMeshes.insert(std::make_pair(
iter->first, textureMesh));
3612 UWARN(
"No camera poses!?");
3618 UWARN(
"No polygons!");
3623 QApplication::processEvents();
3630 if(textureMeshes.size() > 1 &&
_ui->checkBox_assemble->isChecked())
3632 UDEBUG(
"Concatenate texture meshes");
3634 QApplication::processEvents();
3636 QApplication::processEvents();
3639 textureMeshes.clear();
3640 textureMeshes.insert(std::make_pair(0, assembledMesh));
3651 const std::map<int, Transform> & poses,
3652 const QMap<int, Signature> & cachedSignatures,
3653 const std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
3654 const std::map<int, LaserScan> & cachedScans,
3657 bool & scansHaveRGB)
const
3659 scansHaveRGB =
false;
3661 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
3663 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr previousCloud;
3664 pcl::IndicesPtr previousIndices;
3666 for(std::map<int, Transform>::const_iterator
iter = poses.lower_bound(1);
iter!=poses.end() && !
_canceled; ++
iter, ++index)
3669 int totalIndices = 0;
3670 if(!
iter->second.isNull())
3672 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
3673 pcl::IndicesPtr
indices(
new std::vector<int>);
3675 if(
_ui->checkBox_regenerate->isChecked())
3679 if(cachedSignatures.contains(
iter->first))
3681 const Signature &
s = cachedSignatures.find(
iter->first).value();
3682 data =
s.sensorData();
3683 cv::Mat image,depth;
3684 data.uncompressData(
3685 _ui->checkBox_fromDepth->isChecked()?&image:0,
3686 _ui->checkBox_fromDepth->isChecked()?&depth:0,
3687 !
_ui->checkBox_fromDepth->isChecked()?&scan:0);
3691 cv::Mat image,depth;
3693 data.uncompressData(
3694 _ui->checkBox_fromDepth->isChecked()?&image:0,
3695 _ui->checkBox_fromDepth->isChecked()?&depth:0,
3696 !
_ui->checkBox_fromDepth->isChecked()?&scan:0);
3699 if(
_ui->checkBox_fromDepth->isChecked() && !
data.imageRaw().empty() && !
data.depthOrRightRaw().empty())
3701 cv::Mat depth =
data.depthRaw();
3702 if(!depth.empty() &&
_ui->spinBox_fillDepthHoles->value() > 0)
3707 if(!depth.empty() &&
3708 !
_ui->lineEdit_distortionModel->text().isEmpty() &&
3709 QFileInfo(
_ui->lineEdit_distortionModel->text()).exists())
3712 model.load(
_ui->lineEdit_distortionModel->text().toStdString());
3713 depth = depth.clone();
3714 model.undistort(depth);
3718 if(!depth.empty() &&
_ui->checkBox_bilateral->isChecked())
3721 _ui->doubleSpinBox_bilateral_sigmaS->value(),
3722 _ui->doubleSpinBox_bilateral_sigmaR->value());
3727 data.setRGBDImage(
data.imageRaw(), depth,
data.cameraModels());
3731 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
3732 std::vector<float> roiRatios;
3733 if(!
_ui->lineEdit_roiRatios->text().isEmpty())
3735 QStringList
values =
_ui->lineEdit_roiRatios->text().split(
' ');
3738 roiRatios.resize(4);
3747 _ui->spinBox_decimation->value() == 0?1:
_ui->spinBox_decimation->value(),
3748 _ui->doubleSpinBox_maxDepth->value(),
3749 _ui->doubleSpinBox_minDepth->value(),
3754 if(cloudWithoutNormals->size())
3757 if(!(
_ui->comboBox_pipeline->currentIndex()==0 &&
_ui->checkBox_meshing->isChecked()) &&
_ui->doubleSpinBox_voxelSize_assembled->value()>0.0)
3760 indices->resize(cloudWithoutNormals->size());
3761 for(
unsigned int i=0;
i<
indices->size(); ++
i)
3768 Eigen::Vector3f viewPoint(0.0
f,0.0
f,0.0
f);
3769 if(
data.cameraModels().size() && !
data.cameraModels()[0].localTransform().isNull())
3771 localTransform =
data.cameraModels()[0].localTransform();
3772 viewPoint[0] =
data.cameraModels()[0].localTransform().x();
3773 viewPoint[1] =
data.cameraModels()[0].localTransform().y();
3774 viewPoint[2] =
data.cameraModels()[0].localTransform().z();
3776 else if(
data.stereoCameraModels().size() && !
data.stereoCameraModels()[0].localTransform().isNull())
3778 localTransform =
data.stereoCameraModels()[0].localTransform();
3779 viewPoint[0] =
data.stereoCameraModels()[0].localTransform().x();
3780 viewPoint[1] =
data.stereoCameraModels()[0].localTransform().y();
3781 viewPoint[2] =
data.stereoCameraModels()[0].localTransform().z();
3784 if(
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
3786 pcl::PointCloud<pcl::Normal>::Ptr normals =
util3d::computeNormals(cloudWithoutNormals,
indices,
_ui->spinBox_normalKSearch->value(),
_ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
3787 pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
3788 if(
_ui->doubleSpinBox_groundNormalsUp->value() > 0.0)
3795 pcl::copyPointCloud(*cloudWithoutNormals, *cloud);
3798 if(
_ui->checkBox_subtraction->isChecked() &&
3799 _ui->doubleSpinBox_subtractPointFilteringRadius->value() > 0.0)
3801 pcl::IndicesPtr beforeSubtractionIndices =
indices;
3802 if( cloud->size() &&
3803 previousCloud.get() != 0 &&
3804 previousIndices.get() != 0 &&
3805 previousIndices->size() &&
3815 _ui->doubleSpinBox_subtractPointFilteringRadius->value(),
3816 _ui->doubleSpinBox_subtractPointFilteringAngle->value(),
3817 _ui->spinBox_subtractFilteringMinPts->value());
3819 previousCloud = cloud;
3820 previousIndices = beforeSubtractionIndices;
3821 previousPose =
iter->second;
3825 else if(!
_ui->checkBox_fromDepth->isChecked() && !scan.
isEmpty())
3828 _ui->spinBox_decimation_scan->value(),
3829 _ui->doubleSpinBox_rangeMin->value(),
3830 _ui->doubleSpinBox_rangeMax->value(),
3831 _ui->doubleSpinBox_voxelSize_assembled->value(),
3832 _ui->spinBox_normalKSearch->value(),
3833 _ui->doubleSpinBox_normalRadiusSearch->value());
3837 scansHaveRGB = scan.
hasRGB();
3841 indices->resize(cloud->size());
3842 for(
unsigned int i=0;
i<
indices->size(); ++
i)
3850 if(cachedSignatures.contains(
iter->first))
3852 const Signature &
s = cachedSignatures.find(
iter->first).value();
3853 weight =
s.getWeight();
3861 UERROR(
"Cloud %d not found in cache!",
iter->first);
3865 else if(
_ui->checkBox_fromDepth->isChecked() &&
uContains(cachedClouds,
iter->first))
3867 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
3868 if(!
_ui->checkBox_meshing->isChecked() &&
3869 _ui->doubleSpinBox_voxelSize_assembled->value() > 0.0)
3872 cachedClouds.at(
iter->first).first,
3873 cachedClouds.at(
iter->first).second,
3874 _ui->doubleSpinBox_voxelSize_assembled->value());
3877 indices->resize(cloudWithoutNormals->size());
3878 for(
unsigned int i=0;
i<cloudWithoutNormals->size(); ++
i)
3885 cloudWithoutNormals = cachedClouds.at(
iter->first).first;
3890 Eigen::Vector3f viewPoint(0.0
f,0.0
f,0.0
f);
3891 std::vector<CameraModel> models;
3892 std::vector<StereoCameraModel> stereoModels;
3893 if(cachedSignatures.contains(
iter->first))
3895 const Signature &
s = cachedSignatures.find(
iter->first).value();
3896 models =
s.sensorData().cameraModels();
3897 stereoModels =
s.sensorData().stereoCameraModels();
3904 if(models.size() && !models[0].localTransform().isNull())
3906 localTransform = models[0].localTransform();
3907 viewPoint[0] = models[0].localTransform().
x();
3908 viewPoint[1] = models[0].localTransform().y();
3909 viewPoint[2] = models[0].localTransform().z();
3911 else if(stereoModels.size() && !stereoModels[0].localTransform().isNull())
3913 localTransform = stereoModels[0].localTransform();
3914 viewPoint[0] = stereoModels[0].localTransform().
x();
3915 viewPoint[1] = stereoModels[0].localTransform().y();
3916 viewPoint[2] = stereoModels[0].localTransform().z();
3920 _progressDialog->
appendText(tr(
"Cached cloud %1 is not found in cached data, the view point for normal computation will not be set (%2/%3).").
arg(
iter->first).
arg(index).arg(poses.size()), Qt::darkYellow);
3923 if(
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
3925 pcl::PointCloud<pcl::Normal>::Ptr normals =
util3d::computeNormals(cloudWithoutNormals,
indices,
_ui->spinBox_normalKSearch->value(),
_ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
3926 pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
3927 if(
_ui->doubleSpinBox_groundNormalsUp->value() > 0.0)
3934 pcl::copyPointCloud(*cloudWithoutNormals, *cloud);
3937 else if(!
_ui->checkBox_fromDepth->isChecked() &&
uContains(cachedScans,
iter->first))
3940 _ui->spinBox_decimation_scan->value(),
3941 _ui->doubleSpinBox_rangeMin->value(),
3942 _ui->doubleSpinBox_rangeMax->value(),
3943 _ui->doubleSpinBox_voxelSize_assembled->value(),
3944 _ui->spinBox_normalKSearch->value(),
3945 _ui->doubleSpinBox_normalRadiusSearch->value());
3949 scansHaveRGB = scan.
hasRGB();
3953 indices->resize(cloud->size());
3954 for(
unsigned int i=0;
i<
indices->size(); ++
i)
3962 if(cachedSignatures.contains(
iter->first))
3964 const Signature &
s = cachedSignatures.find(
iter->first).value();
3965 weight =
s.getWeight();
3973 _progressDialog->
appendText(tr(
"Cached cloud %1 not found. You may want to regenerate the clouds (%2/%3).").
arg(
iter->first).
arg(index).arg(poses.size()), Qt::darkYellow);
3977 if(
_ui->checkBox_filtering->isChecked())
3980 (
_ui->doubleSpinBox_ceilingHeight->value() != 0.0 ||
3981 _ui->doubleSpinBox_floorHeight->value() != 0.0))
3983 float min =
_ui->doubleSpinBox_floorHeight->value();
3984 float max =
_ui->doubleSpinBox_ceilingHeight->value();
3993 (
_ui->doubleSpinBox_footprintHeight->value() != 0.0 &&
3994 _ui->doubleSpinBox_footprintWidth->value() != 0.0 &&
3995 _ui->doubleSpinBox_footprintLength->value() != 0.0))
3998 float h =
_ui->doubleSpinBox_footprintHeight->value();
3999 float w =
_ui->doubleSpinBox_footprintWidth->value();
4000 float l =
_ui->doubleSpinBox_footprintLength->value();
4019 _ui->doubleSpinBox_filteringRadius->value() > 0.0f &&
4020 _ui->spinBox_filteringMinNeighbors->value() > 0)
4025 UWARN(
"Point cloud %d doesn't have anymore points (had %d points) after radius filtering.",
iter->first, (
int)cloud->size());
4028 if( !
indices->empty() &&
_ui->groupBox_offAxisFiltering->isChecked() &&
4029 (
_ui->checkBox_offAxisFilteringPosX->isChecked() ||
4030 _ui->checkBox_offAxisFilteringNegX->isChecked() ||
4031 _ui->checkBox_offAxisFilteringPosY->isChecked() ||
4032 _ui->checkBox_offAxisFilteringNegY->isChecked() ||
4033 _ui->checkBox_offAxisFilteringPosZ->isChecked() ||
4034 _ui->checkBox_offAxisFilteringNegZ->isChecked()))
4037 std::vector<pcl::IndicesPtr> indicesVector;
4038 double maxDeltaAngle =
_ui->doubleSpinBox_offAxisFilteringAngle->value()*
M_PI/180.0;
4039 Eigen::Vector4f viewpoint(
iter->second.x(),
iter->second.y(),
iter->second.z(), 0);
4040 if(
_ui->checkBox_offAxisFilteringPosX->isChecked())
4042 if(
_ui->checkBox_offAxisFilteringPosY->isChecked())
4044 if(
_ui->checkBox_offAxisFilteringPosZ->isChecked())
4046 if(
_ui->checkBox_offAxisFilteringNegX->isChecked())
4048 if(
_ui->checkBox_offAxisFilteringNegY->isChecked())
4050 if(
_ui->checkBox_offAxisFilteringNegZ->isChecked())
4055 UWARN(
"Point cloud %d doesn't have anymore points (had %d points) after offaxis filtering.",
iter->first, (
int)cloud->size());
4062 if((
_ui->comboBox_frame->isEnabled() &&
_ui->comboBox_frame->currentIndex()==2) && cloud->isOrganized())
4066 else if(
_ui->comboBox_frame->isEnabled() &&
_ui->comboBox_frame->currentIndex()==3)
4071 clouds.insert(std::make_pair(
iter->first, std::make_pair(cloud,
indices)));
4072 points = (
int)cloud->size();
4078 UERROR(
"transform is null!?");
4083 if(
_ui->checkBox_regenerate->isChecked())
4086 .
arg(
iter->first).
arg(points).arg(totalIndices).arg(index).arg(poses.size()));
4091 .
arg(
iter->first).
arg(points).arg(totalIndices).arg(index).arg(poses.size()));
4099 QApplication::processEvents();
4107 const QString & workingDirectory,
4108 const std::map<int, Transform> & poses,
4109 const std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds,
4111 const std::vector<std::map<int, pcl::PointXY> > & pointToPixels)
4113 if(clouds.size() == 1)
4116 QString
extensions = tr(
"Point cloud data (*.ply *.pcd");
4118 for(std::list<std::string>::iterator
iter=pdalFormats.begin();
iter!=pdalFormats.end(); ++
iter)
4120 if(
iter->compare(
"ply") == 0 ||
iter->compare(
"pcd") == 0 ||
iter->compare(
"laz") == 0)
4125 if(
iter->compare(
"las") == 0)
4131 #elif defined(RTABMAP_LIBLAS)
4132 QString
extensions = tr(
"Point cloud data (*.ply *.pcd *.las *.laz)");
4134 QString
extensions = tr(
"Point cloud data (*.ply *.pcd)");
4136 QString
path = QFileDialog::getSaveFileName(
this, tr(
"Save cloud to ..."), workingDirectory+QDir::separator()+
"cloud.ply",
extensions);
4140 if(QFileInfo(
path).suffix().isEmpty())
4146 if(clouds.begin()->second->size())
4148 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudRGBWithoutNormals;
4149 pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIWithoutNormals;
4150 pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloudIWithNormals;
4152 !(
_ui->checkBox_cameraProjection->isEnabled() &&
4153 _ui->checkBox_cameraProjection->isChecked() &&
4154 _ui->checkBox_camProjRecolorPoints->isChecked() &&
4155 clouds.size()==1 && clouds.begin()->first==0))
4158 if(
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
4160 cloudIWithNormals.reset(
new pcl::PointCloud<pcl::PointXYZINormal>);
4161 cloudIWithNormals->resize(clouds.begin()->second->size());
4162 for(
unsigned int i=0;
i<cloudIWithNormals->size(); ++
i)
4164 cloudIWithNormals->points[
i].x = clouds.begin()->second->points[
i].x;
4165 cloudIWithNormals->points[
i].y = clouds.begin()->second->points[
i].y;
4166 cloudIWithNormals->points[
i].z = clouds.begin()->second->points[
i].z;
4167 cloudIWithNormals->points[
i].normal_x = clouds.begin()->second->points[
i].normal_x;
4168 cloudIWithNormals->points[
i].normal_y = clouds.begin()->second->points[
i].normal_y;
4169 cloudIWithNormals->points[
i].normal_z = clouds.begin()->second->points[
i].normal_z;
4170 cloudIWithNormals->points[
i].curvature = clouds.begin()->second->points[
i].curvature;
4171 int * intensity = (
int *)&cloudIWithNormals->points[
i].intensity;
4173 int(clouds.begin()->second->points[
i].r) |
4174 int(clouds.begin()->second->points[
i].g) << 8 |
4175 int(clouds.begin()->second->points[
i].b) << 16 |
4176 int(clouds.begin()->second->points[
i].a) << 24;
4181 cloudIWithoutNormals.reset(
new pcl::PointCloud<pcl::PointXYZI>);
4182 cloudIWithoutNormals->resize(clouds.begin()->second->size());
4183 for(
unsigned int i=0;
i<cloudIWithoutNormals->size(); ++
i)
4185 cloudIWithoutNormals->points[
i].x = clouds.begin()->second->points[
i].x;
4186 cloudIWithoutNormals->points[
i].y = clouds.begin()->second->points[
i].y;
4187 cloudIWithoutNormals->points[
i].z = clouds.begin()->second->points[
i].z;
4188 int * intensity = (
int *)&cloudIWithoutNormals->points[
i].intensity;
4190 int(clouds.begin()->second->points[
i].r) |
4191 int(clouds.begin()->second->points[
i].g) << 8 |
4192 int(clouds.begin()->second->points[
i].b) << 16 |
4193 int(clouds.begin()->second->points[
i].a) << 24;
4197 else if(
_ui->spinBox_normalKSearch->value()<=0 &&
_ui->doubleSpinBox_normalRadiusSearch->value()<=0.0)
4199 cloudRGBWithoutNormals.reset(
new pcl::PointCloud<pcl::PointXYZRGB>);
4200 pcl::copyPointCloud(*clouds.begin()->second, *cloudRGBWithoutNormals);
4205 bool success =
false;
4206 if(QFileInfo(
path).suffix() ==
"pcd")
4208 if(cloudIWithNormals.get())
4210 success = pcl::io::savePCDFile(
path.toStdString(), *cloudIWithNormals, binaryMode) == 0;
4212 else if(cloudIWithoutNormals.get())
4214 success = pcl::io::savePCDFile(
path.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
4216 else if(cloudRGBWithoutNormals.get())
4218 success = pcl::io::savePCDFile(
path.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
4222 success = pcl::io::savePCDFile(
path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
4226 else if(QFileInfo(
path).suffix() ==
"ply" && pointToPixels.empty()) {
4228 else if(QFileInfo(
path).suffix() ==
"ply") {
4230 if(cloudIWithNormals.get())
4232 success = pcl::io::savePLYFile(
path.toStdString(), *cloudIWithNormals, binaryMode) == 0;
4234 else if(cloudIWithoutNormals.get())
4236 success = pcl::io::savePLYFile(
path.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
4238 else if(cloudRGBWithoutNormals.get())
4240 success = pcl::io::savePLYFile(
path.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
4244 success = pcl::io::savePLYFile(
path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
4247 #if defined(RTABMAP_PDAL) || defined(RTABMAP_LIBLAS)
4248 else if(!QFileInfo(
path).suffix().isEmpty())
4250 std::vector<int> cameraIds(pointToPixels.size(), 0);
4251 for(
size_t i=0;
i<pointToPixels.size(); ++
i)
4253 if(!pointToPixels[
i].
empty())
4255 cameraIds[
i] = pointToPixels[
i].begin()->first;
4258 if(cloudIWithNormals.get())
4261 success =
savePDALFile(
path.toStdString(), *cloudIWithNormals, cameraIds, binaryMode) == 0;
4263 UERROR(
"Normals cannot be save with current libLAS implementation, disable normals estimation.");
4267 else if(cloudIWithoutNormals.get())
4270 success =
savePDALFile(
path.toStdString(), *cloudIWithoutNormals, cameraIds, binaryMode) == 0;
4272 success =
saveLASFile(
path.toStdString(), *cloudIWithoutNormals, cameraIds) == 0;
4275 else if(cloudRGBWithoutNormals.get())
4278 success =
savePDALFile(
path.toStdString(), *cloudRGBWithoutNormals, cameraIds, binaryMode) == 0;
4280 success =
saveLASFile(
path.toStdString(), *cloudRGBWithoutNormals, cameraIds) == 0;
4286 success =
savePDALFile(
path.toStdString(), *clouds.begin()->second, cameraIds, binaryMode) == 0;
4288 UERROR(
"Normals cannot be save with current libLAS implementation, disable normals estimation.");
4296 UERROR(
"Extension not recognized! (%s) Should be one of (*.ply *.pcd *.las).", QFileInfo(
path).suffix().toStdString().
c_str());
4303 QMessageBox::information(
this, tr(
"Save successful!"), tr(
"Cloud saved to \"%1\"").
arg(
path));
4307 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Failed to save to \"%1\"").
arg(
path));
4312 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Cloud is empty..."));
4316 else if(clouds.size())
4319 items.push_back(
"ply");
4320 items.push_back(
"pcd");
4322 QString
extensions = tr(
"Save clouds to (*.ply *.pcd");
4324 for(std::list<std::string>::iterator
iter=pdalFormats.begin();
iter!=pdalFormats.end(); ++
iter)
4326 if(
iter->compare(
"ply") == 0 ||
iter->compare(
"pcd") == 0 ||
iter->compare(
"laz") == 0)
4332 items.push_back(
iter->c_str());
4334 if(
iter->compare(
"las") == 0)
4337 items.push_back(
"laz");
4341 #elif defined(RTABMAP_LIBLAS)
4342 QString
extensions = tr(
"Save clouds to (*.ply *.pcd *.las *.laz)...");
4344 QString
extensions = tr(
"Save clouds to (*.ply *.pcd)...");
4346 QString
path = QFileDialog::getExistingDirectory(
this,
extensions, workingDirectory, QFileDialog::ShowDirsOnly);
4350 QString suffix = QInputDialog::getItem(
this, tr(
"File format"), tr(
"Which format?"), items, 0,
false, &ok);
4354 QString prefix = QInputDialog::getText(
this, tr(
"File prefix"), tr(
"Prefix:"), QLineEdit::Normal,
"cloud", &ok);
4358 for(std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::const_iterator
iter=clouds.begin();
iter!=clouds.end(); ++
iter)
4360 if(
iter->second->size())
4362 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformedCloud;
4365 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudRGBWithoutNormals;
4366 pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIWithoutNormals;
4367 pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloudIWithNormals;
4371 if(
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
4373 cloudIWithNormals.reset(
new pcl::PointCloud<pcl::PointXYZINormal>);
4374 cloudIWithNormals->resize(transformedCloud->size());
4375 for(
unsigned int i=0;
i<cloudIWithNormals->size(); ++
i)
4377 cloudIWithNormals->points[
i].x = transformedCloud->points[
i].x;
4378 cloudIWithNormals->points[
i].y = transformedCloud->points[
i].y;
4379 cloudIWithNormals->points[
i].z = transformedCloud->points[
i].z;
4380 cloudIWithNormals->points[
i].normal_x = transformedCloud->points[
i].normal_x;
4381 cloudIWithNormals->points[
i].normal_y = transformedCloud->points[
i].normal_y;
4382 cloudIWithNormals->points[
i].normal_z = transformedCloud->points[
i].normal_z;
4383 cloudIWithNormals->points[
i].curvature = transformedCloud->points[
i].curvature;
4384 int * intensity = (
int *)&cloudIWithNormals->points[
i].intensity;
4386 int(transformedCloud->points[
i].r) |
4387 int(transformedCloud->points[
i].g) << 8 |
4388 int(transformedCloud->points[
i].b) << 16 |
4389 int(transformedCloud->points[
i].a) << 24;
4394 cloudIWithoutNormals.reset(
new pcl::PointCloud<pcl::PointXYZI>);
4395 cloudIWithoutNormals->resize(transformedCloud->size());
4396 for(
unsigned int i=0;
i<cloudIWithoutNormals->size(); ++
i)
4398 cloudIWithoutNormals->points[
i].x = transformedCloud->points[
i].x;
4399 cloudIWithoutNormals->points[
i].y = transformedCloud->points[
i].y;
4400 cloudIWithoutNormals->points[
i].z = transformedCloud->points[
i].z;
4401 int * intensity = (
int *)&cloudIWithoutNormals->points[
i].intensity;
4403 int(transformedCloud->points[
i].r) |
4404 int(transformedCloud->points[
i].g) << 8 |
4405 int(transformedCloud->points[
i].b) << 16 |
4406 int(transformedCloud->points[
i].a) << 24;
4410 else if(
_ui->spinBox_normalKSearch->value()<=0 &&
_ui->doubleSpinBox_normalRadiusSearch->value()<=0.0)
4412 cloudRGBWithoutNormals.reset(
new pcl::PointCloud<pcl::PointXYZRGB>);
4413 pcl::copyPointCloud(*transformedCloud, *cloudRGBWithoutNormals);
4416 QString pathFile =
path+QDir::separator()+QString(
"%1%2.%3").arg(prefix).arg(
iter->first).arg(suffix);
4417 bool success =
false;
4420 if(cloudIWithNormals.get())
4422 success = pcl::io::savePCDFile(pathFile.toStdString(), *cloudIWithNormals, binaryMode) == 0;
4424 else if(cloudIWithoutNormals.get())
4426 success = pcl::io::savePCDFile(pathFile.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
4428 else if(cloudRGBWithoutNormals.get())
4430 success = pcl::io::savePCDFile(pathFile.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
4434 success = pcl::io::savePCDFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
4437 else if(suffix ==
"ply")
4439 if(cloudIWithNormals.get())
4441 success = pcl::io::savePLYFile(pathFile.toStdString(), *cloudIWithNormals, binaryMode) == 0;
4443 else if(cloudIWithoutNormals.get())
4445 success = pcl::io::savePLYFile(pathFile.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
4447 else if(cloudRGBWithoutNormals.get())
4449 success = pcl::io::savePLYFile(pathFile.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
4453 success = pcl::io::savePLYFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
4456 #if defined(RTABMAP_PDAL) || defined(RTABMAP_LIBLAS)
4457 else if(!suffix.isEmpty())
4459 if(cloudIWithNormals.get())
4462 success =
savePDALFile(pathFile.toStdString(), *cloudIWithNormals) == 0;
4464 UERROR(
"Normals cannot be save with current libLAS implementation, disable normals estimation.");
4468 else if(cloudIWithoutNormals.get())
4471 success =
savePDALFile(pathFile.toStdString(), *cloudIWithoutNormals) == 0;
4473 success =
saveLASFile(pathFile.toStdString(), *cloudIWithoutNormals) == 0;
4476 else if(cloudRGBWithoutNormals.get())
4479 success =
savePDALFile(pathFile.toStdString(), *cloudRGBWithoutNormals) == 0;
4481 success =
saveLASFile(pathFile.toStdString(), *cloudRGBWithoutNormals) == 0;
4487 success =
savePDALFile(pathFile.toStdString(), *transformedCloud) == 0;
4489 UERROR(
"Normals cannot be save with current libLAS implementation, disable normals estimation.");
4497 UFATAL(
"Extension not recognized! (%s)", suffix.toStdString().c_str());
4514 QApplication::processEvents();
4527 const QString & workingDirectory,
4528 const std::map<int, Transform> & poses,
4529 const std::map<int, pcl::PolygonMesh::Ptr> & meshes,
4532 if(meshes.size() == 1)
4534 QString
path = QFileDialog::getSaveFileName(
this, tr(
"Save mesh to ..."), workingDirectory+QDir::separator()+
"mesh.ply", tr(
"Mesh (*.ply)"));
4537 if(meshes.begin()->second->polygons.size())
4540 QApplication::processEvents();
4542 QApplication::processEvents();
4544 bool success =
false;
4545 if(QFileInfo(
path).suffix() ==
"")
4550 if(QFileInfo(
path).suffix() ==
"ply")
4554 success = pcl::io::savePLYFileBinary(
path.toStdString(), *meshes.begin()->second) == 0;
4558 success = pcl::io::savePLYFile(
path.toStdString(), *meshes.begin()->second) == 0;
4561 else if(QFileInfo(
path).suffix() ==
"obj")
4567 UERROR(
"Extension not recognized! (%s) Should be (*.ply) or (*.obj).", QFileInfo(
path).suffix().toStdString().
c_str());
4574 QMessageBox::information(
this, tr(
"Save successful!"), tr(
"Mesh saved to \"%1\"").
arg(
path));
4578 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Failed to save to \"%1\"").
arg(
path));
4583 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Cloud is empty..."));
4587 else if(meshes.size())
4589 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Save meshes to (*.ply *.obj)..."), workingDirectory, QFileDialog::ShowDirsOnly);
4594 items.push_back(
"ply");
4595 items.push_back(
"obj");
4596 QString suffix = QInputDialog::getItem(
this, tr(
"File format"), tr(
"Which format?"), items, 0,
false, &ok);
4600 QString prefix = QInputDialog::getText(
this, tr(
"File prefix"), tr(
"Prefix:"), QLineEdit::Normal,
"mesh", &ok);
4604 for(std::map<int, pcl::PolygonMesh::Ptr>::const_iterator
iter=meshes.begin();
iter!=meshes.end(); ++
iter)
4606 if(
iter->second->polygons.size())
4608 pcl::PolygonMesh mesh;
4609 mesh.polygons =
iter->second->polygons;
4611 for(
unsigned int i=0;
i<
iter->second->cloud.fields.size(); ++
i)
4613 if(
iter->second->cloud.fields[
i].name.compare(
"rgb") == 0)
4621 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(
new pcl::PointCloud<pcl::PointXYZRGB>);
4622 pcl::fromPCLPointCloud2(
iter->second->cloud, *tmp);
4624 pcl::toPCLPointCloud2(*tmp, mesh.cloud);
4628 pcl::PointCloud<pcl::PointXYZ>::Ptr tmp(
new pcl::PointCloud<pcl::PointXYZ>);
4629 pcl::fromPCLPointCloud2(
iter->second->cloud, *tmp);
4631 pcl::toPCLPointCloud2(*tmp, mesh.cloud);
4634 QString pathFile =
path+QDir::separator()+QString(
"%1%2.%3").arg(prefix).arg(
iter->first).arg(suffix);
4635 bool success =
false;
4640 success = pcl::io::savePLYFileBinary(pathFile.toStdString(), mesh) == 0;
4644 success = pcl::io::savePLYFile(pathFile.toStdString(), mesh) == 0;
4647 else if(suffix ==
"obj")
4653 UFATAL(
"Extension not recognized! (%s)", suffix.toStdString().c_str());
4658 .
arg(
iter->first).
arg(
iter->second->polygons.size()).arg(pathFile));
4663 .
arg(
iter->first).
arg(
iter->second->polygons.size()).arg(pathFile), Qt::darkRed);
4672 QApplication::processEvents();
4685 const QString & workingDirectory,
4686 const std::map<int, Transform> & poses,
4687 std::map<int, pcl::TextureMesh::Ptr> & meshes,
4688 const QMap<int, Signature> & cachedSignatures,
4689 const std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels)
4691 std::map<int, cv::Mat> images;
4692 std::map<int, std::vector<CameraModel> > calibrations;
4693 for(QMap<int, Signature>::const_iterator
iter=cachedSignatures.constBegin();
iter!=cachedSignatures.constEnd(); ++
iter)
4695 std::vector<CameraModel> models;
4696 if(
iter->sensorData().cameraModels().size())
4698 models =
iter->sensorData().cameraModels();
4700 else if(
iter->sensorData().stereoCameraModels().size())
4702 for(
size_t i=0;
i<
iter->sensorData().stereoCameraModels().
size(); ++
i)
4704 models.push_back(
iter->sensorData().stereoCameraModels()[
i].left());
4710 if(!
iter->sensorData().imageRaw().empty())
4712 calibrations.insert(std::make_pair(
iter.key(), models));
4713 images.insert(std::make_pair(
iter.key(),
iter->sensorData().imageRaw()));
4715 else if(!
iter->sensorData().imageCompressed().empty())
4717 calibrations.insert(std::make_pair(
iter.key(), models));
4718 images.insert(std::make_pair(
iter.key(),
iter->sensorData().imageCompressed()));
4722 int textureSize = 1024;
4723 if(
_ui->comboBox_meshingTextureSize->currentIndex() > 0)
4725 textureSize = 128 <<
_ui->comboBox_meshingTextureSize->currentIndex();
4727 int blendingDecimation = 0;
4728 if(
_ui->checkBox_blending->isChecked())
4730 if(
_ui->comboBox_blendingDecimation->currentIndex() > 0)
4732 blendingDecimation = 1 << (
_ui->comboBox_blendingDecimation->currentIndex()-1);
4736 if(meshes.size() == 1)
4738 QString
path = QFileDialog::getSaveFileName(
this, tr(
"Save texture mesh to ..."), workingDirectory+QDir::separator()+
"mesh.obj", tr(
"Mesh (*.obj)"));
4741 if(meshes.begin()->second->tex_materials.size())
4744 QApplication::processEvents();
4746 QApplication::processEvents();
4748 bool success =
false;
4749 if(QFileInfo(
path).suffix() ==
"")
4754 pcl::TextureMesh::Ptr mesh = meshes.begin()->second;
4756 cv::Mat globalTextures;
4757 bool texturesMerged =
_ui->comboBox_meshingTextureSize->isEnabled() &&
_ui->comboBox_meshingTextureSize->currentIndex() > 0;
4758 if(texturesMerged && mesh->tex_materials.size()>1)
4761 QApplication::processEvents();
4763 QApplication::processEvents();
4765 std::map<int, std::map<int, cv::Vec4d> > gains;
4766 std::map<int, std::map<int, cv::Mat> > blendingGains;
4767 std::pair<float, float> contrastValues(0,0);
4775 _ui->checkBox_multiband->isEnabled() &&
_ui->checkBox_multiband->isChecked()?1:
_ui->spinBox_mesh_maxTextures->value(),
4776 textureVertexToPixels,
4777 _ui->checkBox_gainCompensation->isChecked(),
4778 _ui->doubleSpinBox_gainBeta->value(),
4779 _ui->checkBox_gainRGB->isChecked(),
4780 _ui->checkBox_blending->isChecked(),
4782 _ui->spinBox_textureBrightnessContrastRatioLow->value(),
4783 _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
4784 _ui->checkBox_exposureFusion->isEnabled() &&
_ui->checkBox_exposureFusion->isChecked(),
4787 _ui->comboBox_texturingColorPolicy->currentIndex() == 1,
4793 QApplication::processEvents();
4795 QApplication::processEvents();
4797 if(
_ui->checkBox_multiband->isEnabled() &&
_ui->checkBox_multiband->isChecked() && mesh->tex_polygons.size() == 1)
4800 QApplication::processEvents();
4802 QApplication::processEvents();
4807 mesh->tex_polygons[0],
4809 textureVertexToPixels,
4815 _ui->spinBox_multiband_downscale->value(),
4816 _ui->lineEdit_multiband_nbcontrib->text().toStdString(),
4817 _ui->comboBox_meshingTextureFormat->currentText().toStdString(),
4822 _ui->comboBox_multiband_unwrap->currentIndex(),
4823 _ui->checkBox_multiband_fillholes->isChecked(),
4824 _ui->spinBox_multiband_padding->value(),
4825 _ui->doubleSpinBox_multiband_bestscore->value(),
4826 _ui->doubleSpinBox_multiband_angle->value(),
4827 _ui->checkBox_multiband_forcevisible->isChecked());
4833 QMessageBox::information(
this, tr(
"Save successful!"), tr(
"Mesh saved to \"%1\"").
arg(
path));
4837 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Failed to save to \"%1\"").
arg(
path));
4843 bool singleTexture = mesh->tex_materials.size() == 1;
4847 QDir(QFileInfo(
path).absoluteDir().absolutePath()).mkdir(QFileInfo(
path).baseName());
4851 cv::Mat previousImage;
4852 int previousTextureId = 0;
4853 std::vector<CameraModel> previousCameraModels;
4856 for(
unsigned int i=0;
i<mesh->tex_materials.size(); ++
i)
4858 if(!mesh->tex_materials[
i].tex_file.empty())
4864 fullPath = QFileInfo(
path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(
path).baseName()+
_ui->comboBox_meshingTextureFormat->currentText();
4868 fullPath = QFileInfo(
path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(
path).baseName()+QDir::separator()+QString(mesh->tex_materials[
i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText();
4870 UDEBUG(
"Saving %s...", fullPath.toStdString().c_str());
4871 if(singleTexture || !QFileInfo(fullPath).exists())
4873 std::list<std::string> texFileSplit =
uSplit(mesh->tex_materials[
i].tex_file,
'_');
4874 if(texFileSplit.size() &&
uIsInteger(texFileSplit.front(),
false))
4876 int textureId =
uStr2Int(texFileSplit.front());
4877 int textureSubCamera = -1;
4878 if(texFileSplit.size() == 2 &&
4881 textureSubCamera =
uStr2Int(texFileSplit.back());
4884 std::vector<CameraModel> cameraModels;
4886 if(textureId == previousTextureId)
4888 image = previousImage;
4889 cameraModels = previousCameraModels;
4893 if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
4895 cachedSignatures.value(textureId).sensorData().uncompressDataConst(&image, 0);
4896 cameraModels = cachedSignatures.value(textureId).sensorData().cameraModels();
4902 data.uncompressDataConst(&image, 0);
4903 std::vector<StereoCameraModel> stereoModels;
4905 if(cameraModels.empty())
4907 for(
size_t i=0;
i<stereoModels.size(); ++
i)
4909 cameraModels.push_back(stereoModels[
i].left());
4914 previousImage = image;
4915 previousCameraModels = cameraModels;
4916 previousTextureId = textureId;
4919 imageSize = image.size();
4920 if(textureSubCamera>=0)
4923 imageSize.width/=cameraModels.size();
4924 image = image.colRange(imageSize.width*textureSubCamera, imageSize.width*(textureSubCamera+1));
4931 if(!cv::imwrite(fullPath.toStdString(), image))
4934 .
arg(mesh->tex_materials[
i].tex_file.c_str()).
arg(fullPath), Qt::darkRed);
4938 else if(imageSize.height && imageSize.width)
4941 cv::Mat image = cv::Mat::ones(imageSize, CV_8UC1)*255;
4942 cv::imwrite(fullPath.toStdString(), image);
4944 else if(!globalTextures.empty())
4946 if(!cv::imwrite(fullPath.toStdString(), globalTextures(
cv::Range::all(), cv::Range(
i*globalTextures.rows, (
i+1)*globalTextures.rows))))
4949 .
arg(mesh->tex_materials[
i].tex_file.c_str()).
arg(fullPath), Qt::darkRed);
4955 UWARN(
"Ignored texture %s (no image size set yet)", mesh->tex_materials[
i].tex_file.c_str());
4960 UWARN(
"File %s already exists!", fullPath.toStdString().c_str());
4965 mesh->tex_materials[
i].tex_file=QFileInfo(
path).baseName().toStdString()+
_ui->comboBox_meshingTextureFormat->currentText().toStdString();
4969 mesh->tex_materials[
i].tex_file=(QFileInfo(
path).baseName()+QDir::separator()+QString(mesh->tex_materials[
i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
4979 QMessageBox::information(
this, tr(
"Save successful!"), tr(
"Mesh saved to \"%1\"").
arg(
path));
4983 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Failed to save to \"%1\"").
arg(
path));
4988 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"No textures..."));
4992 else if(meshes.size())
4994 QString
path = QFileDialog::getExistingDirectory(
this, tr(
"Save texture meshes to (*.obj)..."), workingDirectory, QFileDialog::ShowDirsOnly);
4998 QString prefix = QInputDialog::getText(
this, tr(
"File prefix"), tr(
"Prefix:"), QLineEdit::Normal,
"mesh", &ok);
4999 QString suffix =
"obj";
5003 for(std::map<int, pcl::TextureMesh::Ptr>::iterator
iter=meshes.begin();
iter!=meshes.end(); ++
iter)
5005 QString currentPrefix=prefix+QString::number(
iter->first);
5006 if(
iter->second->tex_materials.size())
5008 pcl::TextureMesh::Ptr mesh =
iter->second;
5009 cv::Mat globalTextures;
5010 bool texturesMerged =
_ui->comboBox_meshingTextureSize->isEnabled() &&
_ui->comboBox_meshingTextureSize->currentIndex() > 0;
5011 if(texturesMerged && mesh->tex_materials.size()>1)
5020 _ui->spinBox_mesh_maxTextures->value(),
5021 textureVertexToPixels,
5022 _ui->checkBox_gainCompensation->isChecked(),
5023 _ui->doubleSpinBox_gainBeta->value(),
5024 _ui->checkBox_gainRGB->isChecked(),
5025 _ui->checkBox_blending->isChecked(),
5027 _ui->spinBox_textureBrightnessContrastRatioLow->value(),
5028 _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
5029 _ui->checkBox_exposureFusion->isEnabled() &&
_ui->checkBox_exposureFusion->isChecked(),
5032 _ui->comboBox_texturingColorPolicy->currentIndex() == 1);
5034 bool singleTexture = mesh->tex_materials.size() == 1;
5038 QDir(
path).mkdir(currentPrefix);
5042 cv::Mat previousImage;
5043 int previousTextureId = 0;
5044 std::vector<CameraModel> previousCameraModels;
5047 for(
unsigned int i=0;
i<mesh->tex_materials.size(); ++
i)
5049 if(!mesh->tex_materials[
i].tex_file.empty())
5051 std::list<std::string> texFileSplit =
uSplit(mesh->tex_materials[
i].tex_file,
'_');
5053 int textureSubCamera = -1;
5054 if(texFileSplit.size() &&
uIsInteger(texFileSplit.front(),
false))
5056 textureId =
uStr2Int(texFileSplit.front());
5057 if(texFileSplit.size() == 2 &&
5060 textureSubCamera =
uStr2Int(texFileSplit.back());
5069 fullPath =
path+QDir::separator()+prefix + QString(mesh->tex_materials[
i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText();
5073 fullPath =
path+QDir::separator()+currentPrefix+QDir::separator()+QString(mesh->tex_materials[
i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText();
5078 std::vector<CameraModel> cameraModels;
5080 if(textureId == previousTextureId)
5082 image = previousImage;
5083 cameraModels = previousCameraModels;
5087 if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
5089 cachedSignatures.value(textureId).sensorData().uncompressDataConst(&image, 0);
5090 cameraModels = cachedSignatures.value(textureId).sensorData().cameraModels();
5096 data.uncompressDataConst(&image, 0);
5097 std::vector<StereoCameraModel> stereoModels;
5099 if(cameraModels.empty())
5101 for(
size_t i=0;
i<stereoModels.size(); ++
i)
5103 cameraModels.push_back(stereoModels[
i].left());
5108 previousImage = image;
5109 previousCameraModels = cameraModels;
5110 previousTextureId = textureId;
5115 imageSize = image.size();
5116 if(textureSubCamera>=0)
5119 imageSize.width/=cameraModels.size();
5120 image = image.colRange(imageSize.width*textureSubCamera, imageSize.width*(textureSubCamera+1));
5127 if(!cv::imwrite(fullPath.toStdString(), image))
5130 .
arg(mesh->tex_materials[
i].tex_file.c_str()).
arg(fullPath), Qt::darkRed);
5134 else if(imageSize.height && imageSize.width)
5137 cv::Mat image = cv::Mat::ones(imageSize, CV_8UC1)*255;
5138 cv::imwrite(fullPath.toStdString(), image);
5140 else if(!globalTextures.empty())
5142 if(!cv::imwrite(fullPath.toStdString(), globalTextures(
cv::Range::all(), cv::Range(
i*globalTextures.rows, (
i+1)*globalTextures.rows))))
5145 .
arg(mesh->tex_materials[
i].tex_file.c_str()).
arg(fullPath), Qt::darkRed);
5151 UWARN(
"Ignored texture %s (no image size set yet)", mesh->tex_materials[
i].tex_file.c_str());
5156 mesh->tex_materials[
i].tex_file=(prefix+ QString(mesh->tex_materials[
i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
5160 mesh->tex_materials[
i].tex_file=(currentPrefix+QDir::separator()+QString(mesh->tex_materials[
i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
5164 pcl::PointCloud<pcl::PointNormal>::Ptr tmp(
new pcl::PointCloud<pcl::PointNormal>);
5165 pcl::fromPCLPointCloud2(mesh->cloud, *tmp);
5167 pcl::toPCLPointCloud2(*tmp, mesh->cloud);
5169 QString pathFile =
path+QDir::separator()+QString(
"%1.%3").arg(currentPrefix).arg(suffix);
5170 bool success =
false;
5177 UFATAL(
"Extension not recognized! (%s)", suffix.toStdString().c_str());
5182 .
arg(
iter->first).
arg(mesh->tex_materials.size()).arg(pathFile));
5187 .
arg(
iter->first).
arg(mesh->tex_materials.size()).arg(pathFile), Qt::darkRed);
5196 QApplication::processEvents();
5211 #if PCL_VERSION_COMPARE(>=, 1, 13, 0)
5212 mesh->tex_coord_indices = std::vector<std::vector<pcl::Vertices>>();
5213 auto nr_meshes =
static_cast<unsigned>(mesh->tex_polygons.size());
5215 for (
unsigned m = 0;
m < nr_meshes;
m++) {
5216 std::vector<pcl::Vertices> ci = mesh->tex_polygons[
m];
5217 for(std::size_t
i = 0;
i < ci.size();
i++) {
5218 for (std::size_t
j = 0;
j < ci[
i].vertices.size();
j++) {
5219 ci[
i].vertices[
j] = ci[
i].vertices.size() * (
i + f_idx) +
j;
5222 mesh->tex_coord_indices.push_back(ci);
5223 f_idx +=
static_cast<unsigned>(mesh->tex_polygons[
m].size());