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> 65 #include <QDesktopWidget> 67 #ifdef RTABMAP_CPUTSDF 68 #include <cpu_tsdf/tsdf_volume_octree.h> 69 #include <cpu_tsdf/marching_cubes_tsdf_octree.h> 72 #ifdef RTABMAP_OPENCHISEL 74 #include <open_chisel/ProjectionIntegrator.h> 75 #include <open_chisel/truncation/QuadraticTruncator.h> 76 #include <open_chisel/weighting/ConstantWeighter.h> 87 _ui =
new Ui_ExportCloudsDialog();
90 connect(
_ui->buttonBox->button(QDialogButtonBox::RestoreDefaults), SIGNAL(clicked()),
this, SLOT(
restoreDefaults()));
91 QPushButton * loadSettingsButton =
_ui->buttonBox->addButton(
"Load Settings", QDialogButtonBox::ActionRole);
92 QPushButton * saveSettingsButton =
_ui->buttonBox->addButton(
"Save Settings", QDialogButtonBox::ActionRole);
93 connect(loadSettingsButton, SIGNAL(clicked()),
this, SLOT(
loadSettings()));
94 connect(saveSettingsButton, SIGNAL(clicked()),
this, SLOT(
saveSettings()));
97 _ui->comboBox_upsamplingMethod->setItemData(1, 0, Qt::UserRole - 1);
99 connect(
_ui->checkBox_fromDepth, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
101 connect(
_ui->checkBox_binary, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
102 connect(
_ui->spinBox_normalKSearch, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
103 connect(
_ui->doubleSpinBox_normalRadiusSearch, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
104 connect(
_ui->comboBox_pipeline, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
106 connect(
_ui->comboBox_meshingApproach, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
109 connect(
_ui->checkBox_regenerate, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
111 connect(
_ui->spinBox_decimation, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
112 connect(
_ui->doubleSpinBox_maxDepth, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
113 connect(
_ui->doubleSpinBox_minDepth, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
114 connect(
_ui->spinBox_decimation_scan, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
115 connect(
_ui->doubleSpinBox_rangeMin, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
116 connect(
_ui->doubleSpinBox_rangeMax, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
117 connect(
_ui->spinBox_fillDepthHoles, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
118 connect(
_ui->spinBox_fillDepthHolesError, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
119 connect(
_ui->lineEdit_roiRatios, SIGNAL(textChanged(
const QString &)),
this, SIGNAL(
configChanged()));
120 connect(
_ui->lineEdit_distortionModel, SIGNAL(textChanged(
const QString &)),
this, SIGNAL(
configChanged()));
123 connect(
_ui->checkBox_bilateral, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
125 connect(
_ui->doubleSpinBox_bilateral_sigmaS, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
126 connect(
_ui->doubleSpinBox_bilateral_sigmaR, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
128 connect(
_ui->checkBox_filtering, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
130 connect(
_ui->doubleSpinBox_filteringRadius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
131 connect(
_ui->spinBox_filteringMinNeighbors, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
133 connect(
_ui->checkBox_assemble, SIGNAL(clicked(
bool)),
this, SIGNAL(
configChanged()));
135 connect(
_ui->doubleSpinBox_voxelSize_assembled, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
136 connect(
_ui->comboBox_frame, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
139 connect(
_ui->checkBox_subtraction, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
141 connect(
_ui->doubleSpinBox_subtractPointFilteringRadius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
142 connect(
_ui->doubleSpinBox_subtractPointFilteringAngle, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
143 connect(
_ui->spinBox_subtractFilteringMinPts, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
145 connect(
_ui->checkBox_smoothing, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
147 connect(
_ui->doubleSpinBox_mlsRadius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
148 connect(
_ui->spinBox_polygonialOrder, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
149 connect(
_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
150 connect(
_ui->doubleSpinBox_sampleStep, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
151 connect(
_ui->spinBox_randomPoints, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
152 connect(
_ui->doubleSpinBox_dilationVoxelSize, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
153 connect(
_ui->spinBox_dilationSteps, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
154 connect(
_ui->doubleSpinBox_mls_outputVoxelSize, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
155 _ui->stackedWidget_upsampling->setCurrentIndex(
_ui->comboBox_upsamplingMethod->currentIndex());
156 connect(
_ui->comboBox_upsamplingMethod, SIGNAL(currentIndexChanged(
int)),
_ui->stackedWidget_upsampling, SLOT(setCurrentIndex(
int)));
159 connect(
_ui->checkBox_gainCompensation, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
161 connect(
_ui->doubleSpinBox_gainRadius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
162 connect(
_ui->doubleSpinBox_gainOverlap, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
163 connect(
_ui->doubleSpinBox_gainBeta, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
164 connect(
_ui->checkBox_gainRGB, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
165 connect(
_ui->checkBox_gainFull, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
166 connect(
_ui->spinBox_textureBrightnessContrastRatioLow, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
167 connect(
_ui->spinBox_textureBrightnessContrastRatioHigh, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
168 connect(
_ui->checkBox_exposureFusion, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
169 connect(
_ui->checkBox_blending, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
170 connect(
_ui->comboBox_blendingDecimation, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
172 connect(
_ui->checkBox_meshing, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
175 connect(
_ui->doubleSpinBox_gp3Radius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
176 connect(
_ui->doubleSpinBox_gp3Mu, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
177 connect(
_ui->doubleSpinBox_meshDecimationFactor, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
179 connect(
_ui->spinBox_meshMaxPolygons, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
181 connect(
_ui->doubleSpinBox_transferColorRadius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
182 connect(
_ui->checkBox_cleanMesh, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
183 connect(
_ui->spinBox_mesh_minClusterSize, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
184 connect(
_ui->checkBox_textureMapping, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
186 connect(
_ui->comboBox_meshingTextureFormat, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
187 connect(
_ui->comboBox_meshingTextureSize, SIGNAL(currentIndexChanged(
int)),
this, SIGNAL(
configChanged()));
188 connect(
_ui->spinBox_mesh_maxTextures, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
189 connect(
_ui->doubleSpinBox_meshingTextureMaxDistance, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
190 connect(
_ui->doubleSpinBox_meshingTextureMaxDepthError, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
191 connect(
_ui->doubleSpinBox_meshingTextureMaxAngle, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
192 connect(
_ui->spinBox_mesh_minTextureClusterSize, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
193 connect(
_ui->lineEdit_meshingTextureRoiRatios, SIGNAL(textChanged(
const QString &)),
this, SIGNAL(
configChanged()));
194 connect(
_ui->checkBox_cameraFilter, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
196 connect(
_ui->doubleSpinBox_cameraFilterRadius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
197 connect(
_ui->doubleSpinBox_cameraFilterAngle, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
198 connect(
_ui->doubleSpinBox_cameraFilterVel, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
199 connect(
_ui->doubleSpinBox_cameraFilterVelRad, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
200 connect(
_ui->doubleSpinBox_laplacianVariance, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
202 connect(
_ui->checkBox_poisson_outputPolygons, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
203 connect(
_ui->checkBox_poisson_manifold, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
204 connect(
_ui->spinBox_poisson_depth, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
205 connect(
_ui->spinBox_poisson_iso, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
206 connect(
_ui->spinBox_poisson_solver, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
207 connect(
_ui->spinBox_poisson_minDepth, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
208 connect(
_ui->doubleSpinBox_poisson_samples, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
209 connect(
_ui->doubleSpinBox_poisson_pointWeight, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
210 connect(
_ui->doubleSpinBox_poisson_scale, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
212 connect(
_ui->doubleSpinBox_cputsdf_size, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
213 connect(
_ui->doubleSpinBox_cputsdf_resolution, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
214 connect(
_ui->doubleSpinBox_cputsdf_tuncPos, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
215 connect(
_ui->doubleSpinBox_cputsdf_tuncNeg, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
216 connect(
_ui->doubleSpinBox_cputsdf_minWeight, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
217 connect(
_ui->doubleSpinBox_cputsdf_flattenRadius, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
218 connect(
_ui->spinBox_cputsdf_randomSplit, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
220 connect(
_ui->checkBox_openchisel_mergeVertices, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
221 connect(
_ui->spinBox_openchisel_chunk_size_x, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
222 connect(
_ui->spinBox_openchisel_chunk_size_y, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
223 connect(
_ui->spinBox_openchisel_chunk_size_z, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
224 connect(
_ui->doubleSpinBox_openchisel_truncation_constant, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
225 connect(
_ui->doubleSpinBox_openchisel_truncation_linear, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
226 connect(
_ui->doubleSpinBox_openchisel_truncation_quadratic, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
227 connect(
_ui->doubleSpinBox_openchisel_truncation_scale, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
228 connect(
_ui->spinBox_openchisel_integration_weight, SIGNAL(valueChanged(
int)),
this, SIGNAL(
configChanged()));
229 connect(
_ui->checkBox_openchisel_use_voxel_carving, SIGNAL(stateChanged(
int)),
this, SIGNAL(
configChanged()));
230 connect(
_ui->doubleSpinBox_openchisel_carving_dist_m, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
231 connect(
_ui->doubleSpinBox_openchisel_near_plane_dist, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
232 connect(
_ui->doubleSpinBox_openchisel_far_plane_dist, SIGNAL(valueChanged(
double)),
this, SIGNAL(
configChanged()));
243 _ui->doubleSpinBox_meshDecimationFactor->setEnabled(
false);
244 _ui->spinBox_meshMaxPolygons->setEnabled(
false);
245 _ui->label_meshDecimation->setEnabled(
false);
246 _ui->label_meshMaxPolygons->setEnabled(
false);
249 #if CV_MAJOR_VERSION < 3 250 _ui->checkBox_exposureFusion->setEnabled(
false);
251 _ui->checkBox_exposureFusion->setChecked(
false);
252 _ui->label_exposureFusion->setEnabled(
false);
264 _ui->groupBox->setVisible(
_ui->comboBox_upsamplingMethod->currentIndex() == 0);
265 _ui->groupBox_2->setVisible(
_ui->comboBox_upsamplingMethod->currentIndex() == 1);
266 _ui->groupBox_3->setVisible(
_ui->comboBox_upsamplingMethod->currentIndex() == 2);
267 _ui->groupBox_4->setVisible(
_ui->comboBox_upsamplingMethod->currentIndex() == 3);
268 _ui->groupBox_5->setVisible(
_ui->comboBox_upsamplingMethod->currentIndex() == 4);
281 _ui->checkBox_assemble->setChecked(
true);
282 _ui->checkBox_assemble->setEnabled(
false);
286 _ui->checkBox_assemble->setEnabled(
true);
299 settings.beginGroup(group);
301 settings.setValue(
"pipeline",
_ui->comboBox_pipeline->currentIndex());
302 settings.setValue(
"from_depth",
_ui->checkBox_fromDepth->isChecked());
303 settings.setValue(
"binary",
_ui->checkBox_binary->isChecked());
304 settings.setValue(
"normals_k",
_ui->spinBox_normalKSearch->value());
305 settings.setValue(
"normals_radius",
_ui->doubleSpinBox_normalRadiusSearch->value());
306 settings.setValue(
"intensity_colormap",
_ui->comboBox_intensityColormap->currentIndex());
308 settings.setValue(
"regenerate",
_ui->checkBox_regenerate->isChecked());
309 settings.setValue(
"regenerate_decimation",
_ui->spinBox_decimation->value());
310 settings.setValue(
"regenerate_max_depth",
_ui->doubleSpinBox_maxDepth->value());
311 settings.setValue(
"regenerate_min_depth",
_ui->doubleSpinBox_minDepth->value());
312 settings.setValue(
"regenerate_scan_decimation",
_ui->spinBox_decimation_scan->value());
313 settings.setValue(
"regenerate_scan_max_range",
_ui->doubleSpinBox_rangeMax->value());
314 settings.setValue(
"regenerate_scan_min_range",
_ui->doubleSpinBox_rangeMin->value());
315 settings.setValue(
"regenerate_fill_size",
_ui->spinBox_fillDepthHoles->value());
316 settings.setValue(
"regenerate_fill_error",
_ui->spinBox_fillDepthHolesError->value());
317 settings.setValue(
"regenerate_roi",
_ui->lineEdit_roiRatios->text());
318 settings.setValue(
"regenerate_distortion_model",
_ui->lineEdit_distortionModel->text());
320 settings.setValue(
"bilateral",
_ui->checkBox_bilateral->isChecked());
321 settings.setValue(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value());
322 settings.setValue(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value());
324 settings.setValue(
"filtering",
_ui->checkBox_filtering->isChecked());
325 settings.setValue(
"filtering_radius",
_ui->doubleSpinBox_filteringRadius->value());
326 settings.setValue(
"filtering_min_neighbors",
_ui->spinBox_filteringMinNeighbors->value());
328 settings.setValue(
"assemble",
_ui->checkBox_assemble->isChecked());
329 settings.setValue(
"assemble_voxel",
_ui->doubleSpinBox_voxelSize_assembled->value());
330 settings.setValue(
"frame",
_ui->comboBox_frame->currentIndex());
332 settings.setValue(
"subtract",
_ui->checkBox_subtraction->isChecked());
333 settings.setValue(
"subtract_point_radius",
_ui->doubleSpinBox_subtractPointFilteringRadius->value());
334 settings.setValue(
"subtract_point_angle",
_ui->doubleSpinBox_subtractPointFilteringAngle->value());
335 settings.setValue(
"subtract_min_neighbors",
_ui->spinBox_subtractFilteringMinPts->value());
337 settings.setValue(
"mls",
_ui->checkBox_smoothing->isChecked());
338 settings.setValue(
"mls_radius",
_ui->doubleSpinBox_mlsRadius->value());
339 settings.setValue(
"mls_polygonial_order",
_ui->spinBox_polygonialOrder->value());
340 settings.setValue(
"mls_upsampling_method",
_ui->comboBox_upsamplingMethod->currentIndex());
341 settings.setValue(
"mls_upsampling_radius",
_ui->doubleSpinBox_sampleRadius->value());
342 settings.setValue(
"mls_upsampling_step",
_ui->doubleSpinBox_sampleStep->value());
343 settings.setValue(
"mls_point_density",
_ui->spinBox_randomPoints->value());
344 settings.setValue(
"mls_dilation_voxel_size",
_ui->doubleSpinBox_dilationVoxelSize->value());
345 settings.setValue(
"mls_dilation_iterations",
_ui->spinBox_dilationSteps->value());
346 settings.setValue(
"mls_output_voxel_size",
_ui->doubleSpinBox_mls_outputVoxelSize->value());
348 settings.setValue(
"gain",
_ui->checkBox_gainCompensation->isChecked());
349 settings.setValue(
"gain_radius",
_ui->doubleSpinBox_gainRadius->value());
350 settings.setValue(
"gain_overlap",
_ui->doubleSpinBox_gainOverlap->value());
351 settings.setValue(
"gain_beta",
_ui->doubleSpinBox_gainBeta->value());
352 settings.setValue(
"gain_rgb",
_ui->checkBox_gainRGB->isChecked());
353 settings.setValue(
"gain_full",
_ui->checkBox_gainFull->isChecked());
355 settings.setValue(
"mesh",
_ui->checkBox_meshing->isChecked());
356 settings.setValue(
"mesh_radius",
_ui->doubleSpinBox_gp3Radius->value());
357 settings.setValue(
"mesh_mu",
_ui->doubleSpinBox_gp3Mu->value());
358 settings.setValue(
"mesh_decimation_factor",
_ui->doubleSpinBox_meshDecimationFactor->value());
359 settings.setValue(
"mesh_max_polygons",
_ui->spinBox_meshMaxPolygons->value());
360 settings.setValue(
"mesh_color_radius",
_ui->doubleSpinBox_transferColorRadius->value());
361 settings.setValue(
"mesh_clean",
_ui->checkBox_cleanMesh->isChecked());
362 settings.setValue(
"mesh_min_cluster_size",
_ui->spinBox_mesh_minClusterSize->value());
364 settings.setValue(
"mesh_dense_strategy",
_ui->comboBox_meshingApproach->currentIndex());
366 settings.setValue(
"mesh_texture",
_ui->checkBox_textureMapping->isChecked());
367 settings.setValue(
"mesh_textureFormat",
_ui->comboBox_meshingTextureFormat->currentIndex());
368 settings.setValue(
"mesh_textureSize",
_ui->comboBox_meshingTextureSize->currentIndex());
369 settings.setValue(
"mesh_textureMaxCount",
_ui->spinBox_mesh_maxTextures->value());
370 settings.setValue(
"mesh_textureMaxDistance",
_ui->doubleSpinBox_meshingTextureMaxDistance->value());
371 settings.setValue(
"mesh_textureMaxDepthError",
_ui->doubleSpinBox_meshingTextureMaxDepthError->value());
372 settings.setValue(
"mesh_textureMaxAngle",
_ui->doubleSpinBox_meshingTextureMaxAngle->value());
373 settings.setValue(
"mesh_textureMinCluster",
_ui->spinBox_mesh_minTextureClusterSize->value());
374 settings.setValue(
"mesh_textureRoiRatios",
_ui->lineEdit_meshingTextureRoiRatios->text());
375 settings.setValue(
"mesh_textureDistanceToCamPolicy",
_ui->checkBox_distanceToCamPolicy->isChecked());
376 settings.setValue(
"mesh_textureCameraFiltering",
_ui->checkBox_cameraFilter->isChecked());
377 settings.setValue(
"mesh_textureCameraFilteringRadius",
_ui->doubleSpinBox_cameraFilterRadius->value());
378 settings.setValue(
"mesh_textureCameraFilteringAngle",
_ui->doubleSpinBox_cameraFilterAngle->value());
379 settings.setValue(
"mesh_textureCameraFilteringVel",
_ui->doubleSpinBox_cameraFilterVel->value());
380 settings.setValue(
"mesh_textureCameraFilteringVelRad",
_ui->doubleSpinBox_cameraFilterVelRad->value());
381 settings.setValue(
"mesh_textureCameraFilteringLaplacian",
_ui->doubleSpinBox_laplacianVariance->value());
382 settings.setValue(
"mesh_textureBrightnessConstrastRatioLow",
_ui->spinBox_textureBrightnessContrastRatioLow->value());
383 settings.setValue(
"mesh_textureBrightnessConstrastRatioHigh",
_ui->spinBox_textureBrightnessContrastRatioHigh->value());
384 settings.setValue(
"mesh_textureExposureFusion",
_ui->checkBox_exposureFusion->isChecked());
385 settings.setValue(
"mesh_textureBlending",
_ui->checkBox_blending->isChecked());
386 settings.setValue(
"mesh_textureBlendingDecimation",
_ui->comboBox_blendingDecimation->currentIndex());
387 settings.setValue(
"mesh_textureMultiband",
_ui->checkBox_multiband->isChecked());
390 settings.setValue(
"mesh_angle_tolerance",
_ui->doubleSpinBox_mesh_angleTolerance->value());
391 settings.setValue(
"mesh_quad",
_ui->checkBox_mesh_quad->isChecked());
392 settings.setValue(
"mesh_triangle_size",
_ui->spinBox_mesh_triangleSize->value());
394 settings.setValue(
"poisson_outputPolygons",
_ui->checkBox_poisson_outputPolygons->isChecked());
395 settings.setValue(
"poisson_manifold",
_ui->checkBox_poisson_manifold->isChecked());
396 settings.setValue(
"poisson_depth",
_ui->spinBox_poisson_depth->value());
397 settings.setValue(
"poisson_iso",
_ui->spinBox_poisson_iso->value());
398 settings.setValue(
"poisson_solver",
_ui->spinBox_poisson_solver->value());
399 settings.setValue(
"poisson_minDepth",
_ui->spinBox_poisson_minDepth->value());
400 settings.setValue(
"poisson_samples",
_ui->doubleSpinBox_poisson_samples->value());
401 settings.setValue(
"poisson_pointWeight",
_ui->doubleSpinBox_poisson_pointWeight->value());
402 settings.setValue(
"poisson_scale",
_ui->doubleSpinBox_poisson_scale->value());
404 settings.setValue(
"cputsdf_size",
_ui->doubleSpinBox_cputsdf_size->value());
405 settings.setValue(
"cputsdf_resolution",
_ui->doubleSpinBox_cputsdf_resolution->value());
406 settings.setValue(
"cputsdf_truncPos",
_ui->doubleSpinBox_cputsdf_tuncPos->value());
407 settings.setValue(
"cputsdf_truncNeg",
_ui->doubleSpinBox_cputsdf_tuncNeg->value());
408 settings.setValue(
"cputsdf_minWeight",
_ui->doubleSpinBox_cputsdf_minWeight->value());
409 settings.setValue(
"cputsdf_flattenRadius",
_ui->doubleSpinBox_cputsdf_flattenRadius->value());
410 settings.setValue(
"cputsdf_randomSplit",
_ui->spinBox_cputsdf_randomSplit->value());
412 settings.setValue(
"openchisel_merge_vertices",
_ui->checkBox_openchisel_mergeVertices->isChecked());
413 settings.setValue(
"openchisel_chunk_size_x",
_ui->spinBox_openchisel_chunk_size_x->value());
414 settings.setValue(
"openchisel_chunk_size_y",
_ui->spinBox_openchisel_chunk_size_y->value());
415 settings.setValue(
"openchisel_chunk_size_z",
_ui->spinBox_openchisel_chunk_size_z->value());
416 settings.setValue(
"openchisel_truncation_constant",
_ui->doubleSpinBox_openchisel_truncation_constant->value());
417 settings.setValue(
"openchisel_truncation_linear",
_ui->doubleSpinBox_openchisel_truncation_linear->value());
418 settings.setValue(
"openchisel_truncation_quadratic",
_ui->doubleSpinBox_openchisel_truncation_quadratic->value());
419 settings.setValue(
"openchisel_truncation_scale",
_ui->doubleSpinBox_openchisel_truncation_scale->value());
420 settings.setValue(
"openchisel_integration_weight",
_ui->spinBox_openchisel_integration_weight->value());
421 settings.setValue(
"openchisel_use_voxel_carving",
_ui->checkBox_openchisel_use_voxel_carving->isChecked());
422 settings.setValue(
"openchisel_carving_dist_m",
_ui->doubleSpinBox_openchisel_carving_dist_m->value());
423 settings.setValue(
"openchisel_near_plane_dist",
_ui->doubleSpinBox_openchisel_near_plane_dist->value());
424 settings.setValue(
"openchisel_far_plane_dist",
_ui->doubleSpinBox_openchisel_far_plane_dist->value());
436 settings.beginGroup(group);
439 _ui->comboBox_pipeline->setCurrentIndex(settings.value(
"pipeline",
_ui->comboBox_pipeline->currentIndex()).toInt());
440 _ui->checkBox_fromDepth->setChecked(settings.value(
"from_depth",
_ui->checkBox_fromDepth->isChecked()).toBool());
441 _ui->checkBox_binary->setChecked(settings.value(
"binary",
_ui->checkBox_binary->isChecked()).toBool());
442 _ui->spinBox_normalKSearch->setValue(settings.value(
"normals_k",
_ui->spinBox_normalKSearch->value()).toInt());
443 _ui->doubleSpinBox_normalRadiusSearch->setValue(settings.value(
"normals_radius",
_ui->doubleSpinBox_normalRadiusSearch->value()).toDouble());
444 _ui->comboBox_intensityColormap->setCurrentIndex(settings.value(
"intensity_colormap",
_ui->comboBox_intensityColormap->currentIndex()).toInt());
446 _ui->checkBox_regenerate->setChecked(settings.value(
"regenerate",
_ui->checkBox_regenerate->isChecked()).toBool());
447 _ui->spinBox_decimation->setValue(settings.value(
"regenerate_decimation",
_ui->spinBox_decimation->value()).toInt());
448 _ui->doubleSpinBox_maxDepth->setValue(settings.value(
"regenerate_max_depth",
_ui->doubleSpinBox_maxDepth->value()).toDouble());
449 _ui->doubleSpinBox_minDepth->setValue(settings.value(
"regenerate_min_depth",
_ui->doubleSpinBox_minDepth->value()).toDouble());
450 _ui->spinBox_decimation_scan->setValue(settings.value(
"regenerate_scan_decimation",
_ui->spinBox_decimation_scan->value()).toInt());
451 _ui->doubleSpinBox_rangeMax->setValue(settings.value(
"regenerate_scan_max_range",
_ui->doubleSpinBox_rangeMax->value()).toDouble());
452 _ui->doubleSpinBox_rangeMin->setValue(settings.value(
"regenerate_scan_min_range",
_ui->doubleSpinBox_rangeMin->value()).toDouble());
453 _ui->spinBox_fillDepthHoles->setValue(settings.value(
"regenerate_fill_size",
_ui->spinBox_fillDepthHoles->value()).toInt());
454 _ui->spinBox_fillDepthHolesError->setValue(settings.value(
"regenerate_fill_error",
_ui->spinBox_fillDepthHolesError->value()).toInt());
455 _ui->lineEdit_roiRatios->setText(settings.value(
"regenerate_roi",
_ui->lineEdit_roiRatios->text()).toString());
456 _ui->lineEdit_distortionModel->setText(settings.value(
"regenerate_distortion_model",
_ui->lineEdit_distortionModel->text()).toString());
458 _ui->checkBox_bilateral->setChecked(settings.value(
"bilateral",
_ui->checkBox_bilateral->isChecked()).toBool());
459 _ui->doubleSpinBox_bilateral_sigmaS->setValue(settings.value(
"bilateral_sigma_s",
_ui->doubleSpinBox_bilateral_sigmaS->value()).toDouble());
460 _ui->doubleSpinBox_bilateral_sigmaR->setValue(settings.value(
"bilateral_sigma_r",
_ui->doubleSpinBox_bilateral_sigmaR->value()).toDouble());
462 _ui->checkBox_filtering->setChecked(settings.value(
"filtering",
_ui->checkBox_filtering->isChecked()).toBool());
463 _ui->doubleSpinBox_filteringRadius->setValue(settings.value(
"filtering_radius",
_ui->doubleSpinBox_filteringRadius->value()).toDouble());
464 _ui->spinBox_filteringMinNeighbors->setValue(settings.value(
"filtering_min_neighbors",
_ui->spinBox_filteringMinNeighbors->value()).toInt());
466 if(
_ui->checkBox_assemble->isEnabled())
468 _ui->checkBox_assemble->setChecked(settings.value(
"assemble",
_ui->checkBox_assemble->isChecked()).toBool());
470 _ui->doubleSpinBox_voxelSize_assembled->setValue(settings.value(
"assemble_voxel",
_ui->doubleSpinBox_voxelSize_assembled->value()).toDouble());
471 _ui->comboBox_frame->setCurrentIndex(settings.value(
"frame",
_ui->comboBox_frame->currentIndex()).toInt());
473 _ui->checkBox_subtraction->setChecked(settings.value(
"subtract",
_ui->checkBox_subtraction->isChecked()).toBool());
474 _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(settings.value(
"subtract_point_radius",
_ui->doubleSpinBox_subtractPointFilteringRadius->value()).toDouble());
475 _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(settings.value(
"subtract_point_angle",
_ui->doubleSpinBox_subtractPointFilteringAngle->value()).toDouble());
476 _ui->spinBox_subtractFilteringMinPts->setValue(settings.value(
"subtract_min_neighbors",
_ui->spinBox_subtractFilteringMinPts->value()).toInt());
478 _ui->checkBox_smoothing->setChecked(settings.value(
"mls",
_ui->checkBox_smoothing->isChecked()).toBool());
479 _ui->doubleSpinBox_mlsRadius->setValue(settings.value(
"mls_radius",
_ui->doubleSpinBox_mlsRadius->value()).toDouble());
480 _ui->spinBox_polygonialOrder->setValue(settings.value(
"mls_polygonial_order",
_ui->spinBox_polygonialOrder->value()).toInt());
481 _ui->comboBox_upsamplingMethod->setCurrentIndex(settings.value(
"mls_upsampling_method",
_ui->comboBox_upsamplingMethod->currentIndex()).toInt());
482 _ui->doubleSpinBox_sampleRadius->setValue(settings.value(
"mls_upsampling_radius",
_ui->doubleSpinBox_sampleRadius->value()).toDouble());
483 _ui->doubleSpinBox_sampleStep->setValue(settings.value(
"mls_upsampling_step",
_ui->doubleSpinBox_sampleStep->value()).toDouble());
484 _ui->spinBox_randomPoints->setValue(settings.value(
"mls_point_density",
_ui->spinBox_randomPoints->value()).toInt());
485 _ui->doubleSpinBox_dilationVoxelSize->setValue(settings.value(
"mls_dilation_voxel_size",
_ui->doubleSpinBox_dilationVoxelSize->value()).toDouble());
486 _ui->spinBox_dilationSteps->setValue(settings.value(
"mls_dilation_iterations",
_ui->spinBox_dilationSteps->value()).toInt());
487 _ui->doubleSpinBox_mls_outputVoxelSize->setValue(settings.value(
"mls_output_voxel_size",
_ui->doubleSpinBox_mls_outputVoxelSize->value()).toInt());
489 _ui->checkBox_gainCompensation->setChecked(settings.value(
"gain",
_ui->checkBox_gainCompensation->isChecked()).toBool());
490 _ui->doubleSpinBox_gainRadius->setValue(settings.value(
"gain_radius",
_ui->doubleSpinBox_gainRadius->value()).toDouble());
491 _ui->doubleSpinBox_gainOverlap->setValue(settings.value(
"gain_overlap",
_ui->doubleSpinBox_gainOverlap->value()).toDouble());
492 _ui->doubleSpinBox_gainBeta->setValue(settings.value(
"gain_beta",
_ui->doubleSpinBox_gainBeta->value()).toDouble());
493 _ui->checkBox_gainRGB->setChecked(settings.value(
"gain_rgb",
_ui->checkBox_gainRGB->isChecked()).toBool());
494 _ui->checkBox_gainFull->setChecked(settings.value(
"gain_full",
_ui->checkBox_gainFull->isChecked()).toBool());
496 _ui->checkBox_meshing->setChecked(settings.value(
"mesh",
_ui->checkBox_meshing->isChecked()).toBool());
497 _ui->doubleSpinBox_gp3Radius->setValue(settings.value(
"mesh_radius",
_ui->doubleSpinBox_gp3Radius->value()).toDouble());
498 _ui->doubleSpinBox_gp3Mu->setValue(settings.value(
"mesh_mu",
_ui->doubleSpinBox_gp3Mu->value()).toDouble());
499 _ui->doubleSpinBox_meshDecimationFactor->setValue(settings.value(
"mesh_decimation_factor",
_ui->doubleSpinBox_meshDecimationFactor->value()).toDouble());
500 _ui->spinBox_meshMaxPolygons->setValue(settings.value(
"mesh_max_polygons",
_ui->spinBox_meshMaxPolygons->value()).toDouble());
501 _ui->doubleSpinBox_transferColorRadius->setValue(settings.value(
"mesh_color_radius",
_ui->doubleSpinBox_transferColorRadius->value()).toDouble());
502 _ui->checkBox_cleanMesh->setChecked(settings.value(
"mesh_clean",
_ui->checkBox_cleanMesh->isChecked()).toBool());
503 _ui->spinBox_mesh_minClusterSize->setValue(settings.value(
"mesh_min_cluster_size",
_ui->spinBox_mesh_minClusterSize->value()).toInt());
505 _ui->comboBox_meshingApproach->setCurrentIndex(settings.value(
"mesh_dense_strategy",
_ui->comboBox_meshingApproach->currentIndex()).toInt());
507 _ui->checkBox_textureMapping->setChecked(settings.value(
"mesh_texture",
_ui->checkBox_textureMapping->isChecked()).toBool());
508 _ui->comboBox_meshingTextureFormat->setCurrentIndex(settings.value(
"mesh_textureFormat",
_ui->comboBox_meshingTextureFormat->currentIndex()).toInt());
509 _ui->comboBox_meshingTextureSize->setCurrentIndex(settings.value(
"mesh_textureSize",
_ui->comboBox_meshingTextureSize->currentIndex()).toInt());
510 _ui->spinBox_mesh_maxTextures->setValue(settings.value(
"mesh_textureMaxCount",
_ui->spinBox_mesh_maxTextures->value()).toInt());
511 _ui->doubleSpinBox_meshingTextureMaxDistance->setValue(settings.value(
"mesh_textureMaxDistance",
_ui->doubleSpinBox_meshingTextureMaxDistance->value()).toDouble());
512 _ui->doubleSpinBox_meshingTextureMaxDepthError->setValue(settings.value(
"mesh_textureMaxDepthError",
_ui->doubleSpinBox_meshingTextureMaxDepthError->value()).toDouble());
513 _ui->doubleSpinBox_meshingTextureMaxAngle->setValue(settings.value(
"mesh_textureMaxAngle",
_ui->doubleSpinBox_meshingTextureMaxAngle->value()).toDouble());
514 _ui->spinBox_mesh_minTextureClusterSize->setValue(settings.value(
"mesh_textureMinCluster",
_ui->spinBox_mesh_minTextureClusterSize->value()).toDouble());
515 _ui->lineEdit_meshingTextureRoiRatios->setText(settings.value(
"mesh_textureRoiRatios",
_ui->lineEdit_meshingTextureRoiRatios->text()).toString());
516 _ui->checkBox_distanceToCamPolicy->setChecked(settings.value(
"mesh_textureDistanceToCamPolicy",
_ui->checkBox_distanceToCamPolicy->isChecked()).toBool());
517 _ui->checkBox_cameraFilter->setChecked(settings.value(
"mesh_textureCameraFiltering",
_ui->checkBox_cameraFilter->isChecked()).toBool());
518 _ui->doubleSpinBox_cameraFilterRadius->setValue(settings.value(
"mesh_textureCameraFilteringRadius",
_ui->doubleSpinBox_cameraFilterRadius->value()).toDouble());
519 _ui->doubleSpinBox_cameraFilterAngle->setValue(settings.value(
"mesh_textureCameraFilteringAngle",
_ui->doubleSpinBox_cameraFilterAngle->value()).toDouble());
520 _ui->doubleSpinBox_cameraFilterVel->setValue(settings.value(
"mesh_textureCameraFilteringVel",
_ui->doubleSpinBox_cameraFilterVel->value()).toDouble());
521 _ui->doubleSpinBox_cameraFilterVelRad->setValue(settings.value(
"mesh_textureCameraFilteringVelRad",
_ui->doubleSpinBox_cameraFilterVelRad->value()).toDouble());
522 _ui->doubleSpinBox_laplacianVariance->setValue(settings.value(
"mesh_textureCameraFilteringLaplacian",
_ui->doubleSpinBox_laplacianVariance->value()).toDouble());
523 _ui->spinBox_textureBrightnessContrastRatioLow->setValue(settings.value(
"mesh_textureBrightnessConstrastRatioLow",
_ui->spinBox_textureBrightnessContrastRatioLow->value()).toDouble());
524 _ui->spinBox_textureBrightnessContrastRatioHigh->setValue(settings.value(
"mesh_textureBrightnessConstrastRatioHigh",
_ui->spinBox_textureBrightnessContrastRatioHigh->value()).toDouble());
525 if(
_ui->checkBox_exposureFusion->isEnabled())
527 _ui->checkBox_exposureFusion->setChecked(settings.value(
"mesh_textureExposureFusion",
_ui->checkBox_exposureFusion->isChecked()).toBool());
529 _ui->checkBox_blending->setChecked(settings.value(
"mesh_textureBlending",
_ui->checkBox_blending->isChecked()).toBool());
530 _ui->comboBox_blendingDecimation->setCurrentIndex(settings.value(
"mesh_textureBlendingDecimation",
_ui->comboBox_blendingDecimation->currentIndex()).toInt());
531 _ui->checkBox_multiband->setChecked(settings.value(
"mesh_textureMultiband",
_ui->checkBox_multiband->isChecked()).toBool());
533 _ui->doubleSpinBox_mesh_angleTolerance->setValue(settings.value(
"mesh_angle_tolerance",
_ui->doubleSpinBox_mesh_angleTolerance->value()).toDouble());
534 _ui->checkBox_mesh_quad->setChecked(settings.value(
"mesh_quad",
_ui->checkBox_mesh_quad->isChecked()).toBool());
535 _ui->spinBox_mesh_triangleSize->setValue(settings.value(
"mesh_triangle_size",
_ui->spinBox_mesh_triangleSize->value()).toInt());
537 _ui->checkBox_poisson_outputPolygons->setChecked(settings.value(
"poisson_outputPolygons",
_ui->checkBox_poisson_outputPolygons->isChecked()).toBool());
538 _ui->checkBox_poisson_manifold->setChecked(settings.value(
"poisson_manifold",
_ui->checkBox_poisson_manifold->isChecked()).toBool());
539 _ui->spinBox_poisson_depth->setValue(settings.value(
"poisson_depth",
_ui->spinBox_poisson_depth->value()).toInt());
540 _ui->spinBox_poisson_iso->setValue(settings.value(
"poisson_iso",
_ui->spinBox_poisson_iso->value()).toInt());
541 _ui->spinBox_poisson_solver->setValue(settings.value(
"poisson_solver",
_ui->spinBox_poisson_solver->value()).toInt());
542 _ui->spinBox_poisson_minDepth->setValue(settings.value(
"poisson_minDepth",
_ui->spinBox_poisson_minDepth->value()).toInt());
543 _ui->doubleSpinBox_poisson_samples->setValue(settings.value(
"poisson_samples",
_ui->doubleSpinBox_poisson_samples->value()).toDouble());
544 _ui->doubleSpinBox_poisson_pointWeight->setValue(settings.value(
"poisson_pointWeight",
_ui->doubleSpinBox_poisson_pointWeight->value()).toDouble());
545 _ui->doubleSpinBox_poisson_scale->setValue(settings.value(
"poisson_scale",
_ui->doubleSpinBox_poisson_scale->value()).toDouble());
547 _ui->doubleSpinBox_cputsdf_size->setValue(settings.value(
"cputsdf_size",
_ui->doubleSpinBox_cputsdf_size->value()).toDouble());
548 _ui->doubleSpinBox_cputsdf_resolution->setValue(settings.value(
"cputsdf_resolution",
_ui->doubleSpinBox_cputsdf_resolution->value()).toDouble());
549 _ui->doubleSpinBox_cputsdf_tuncPos->setValue(settings.value(
"cputsdf_truncPos",
_ui->doubleSpinBox_cputsdf_tuncPos->value()).toDouble());
550 _ui->doubleSpinBox_cputsdf_tuncNeg->setValue(settings.value(
"cputsdf_truncNeg",
_ui->doubleSpinBox_cputsdf_tuncNeg->value()).toDouble());
551 _ui->doubleSpinBox_cputsdf_minWeight->setValue(settings.value(
"cputsdf_minWeight",
_ui->doubleSpinBox_cputsdf_minWeight->value()).toDouble());
552 _ui->doubleSpinBox_cputsdf_flattenRadius->setValue(settings.value(
"cputsdf_flattenRadius",
_ui->doubleSpinBox_cputsdf_flattenRadius->value()).toDouble());
553 _ui->spinBox_cputsdf_randomSplit->setValue(settings.value(
"cputsdf_randomSplit",
_ui->spinBox_cputsdf_randomSplit->value()).toInt());
555 _ui->checkBox_openchisel_mergeVertices->setChecked(settings.value(
"openchisel_merge_vertices",
_ui->checkBox_openchisel_mergeVertices->isChecked()).toBool());
556 _ui->spinBox_openchisel_chunk_size_x->setValue(settings.value(
"openchisel_chunk_size_x",
_ui->spinBox_openchisel_chunk_size_x->value()).toInt());
557 _ui->spinBox_openchisel_chunk_size_y->setValue(settings.value(
"openchisel_chunk_size_y",
_ui->spinBox_openchisel_chunk_size_y->value()).toInt());
558 _ui->spinBox_openchisel_chunk_size_z->setValue(settings.value(
"openchisel_chunk_size_z",
_ui->spinBox_openchisel_chunk_size_z->value()).toInt());
559 _ui->doubleSpinBox_openchisel_truncation_constant->setValue(settings.value(
"openchisel_truncation_constant",
_ui->doubleSpinBox_openchisel_truncation_constant->value()).toDouble());
560 _ui->doubleSpinBox_openchisel_truncation_linear->setValue(settings.value(
"openchisel_truncation_linear",
_ui->doubleSpinBox_openchisel_truncation_linear->value()).toDouble());
561 _ui->doubleSpinBox_openchisel_truncation_quadratic->setValue(settings.value(
"openchisel_truncation_quadratic",
_ui->doubleSpinBox_openchisel_truncation_quadratic->value()).toDouble());
562 _ui->doubleSpinBox_openchisel_truncation_scale->setValue(settings.value(
"openchisel_truncation_scale",
_ui->doubleSpinBox_openchisel_truncation_scale->value()).toDouble());
563 _ui->spinBox_openchisel_integration_weight->setValue(settings.value(
"openchisel_integration_weight",
_ui->spinBox_openchisel_integration_weight->value()).toInt());
564 _ui->checkBox_openchisel_use_voxel_carving->setChecked(settings.value(
"openchisel_use_voxel_carving",
_ui->checkBox_openchisel_use_voxel_carving->isChecked()).toBool());
565 _ui->doubleSpinBox_openchisel_carving_dist_m->setValue(settings.value(
"openchisel_carving_dist_m",
_ui->doubleSpinBox_openchisel_carving_dist_m->value()).toDouble());
566 _ui->doubleSpinBox_openchisel_near_plane_dist->setValue(settings.value(
"openchisel_near_plane_dist",
_ui->doubleSpinBox_openchisel_near_plane_dist->value()).toDouble());
567 _ui->doubleSpinBox_openchisel_far_plane_dist->setValue(settings.value(
"openchisel_far_plane_dist",
_ui->doubleSpinBox_openchisel_far_plane_dist->value()).toDouble());
580 _ui->comboBox_pipeline->setCurrentIndex(1);
581 _ui->checkBox_fromDepth->setChecked(
true);
582 _ui->checkBox_binary->setChecked(
true);
583 _ui->spinBox_normalKSearch->setValue(20);
584 _ui->doubleSpinBox_normalRadiusSearch->setValue(0.0);
585 _ui->comboBox_intensityColormap->setCurrentIndex(0);
587 _ui->checkBox_regenerate->setChecked(
_dbDriver!=0?
true:
false);
588 _ui->spinBox_decimation->setValue(1);
589 _ui->doubleSpinBox_maxDepth->setValue(4);
590 _ui->doubleSpinBox_minDepth->setValue(0);
591 _ui->spinBox_decimation_scan->setValue(1);
592 _ui->doubleSpinBox_rangeMax->setValue(0);
593 _ui->doubleSpinBox_rangeMin->setValue(0);
594 _ui->spinBox_fillDepthHoles->setValue(0);
595 _ui->spinBox_fillDepthHolesError->setValue(2);
596 _ui->lineEdit_roiRatios->setText(
"0.0 0.0 0.0 0.0");
597 _ui->lineEdit_distortionModel->setText(
"");
599 _ui->checkBox_bilateral->setChecked(
false);
600 _ui->doubleSpinBox_bilateral_sigmaS->setValue(10.0);
601 _ui->doubleSpinBox_bilateral_sigmaR->setValue(0.1);
603 _ui->checkBox_filtering->setChecked(
false);
604 _ui->doubleSpinBox_filteringRadius->setValue(0.02);
605 _ui->spinBox_filteringMinNeighbors->setValue(2);
607 _ui->checkBox_assemble->setChecked(
true);
608 _ui->doubleSpinBox_voxelSize_assembled->setValue(0.01);
609 _ui->comboBox_frame->setCurrentIndex(0);
611 _ui->checkBox_subtraction->setChecked(
false);
612 _ui->doubleSpinBox_subtractPointFilteringRadius->setValue(0.02);
613 _ui->doubleSpinBox_subtractPointFilteringAngle->setValue(0);
614 _ui->spinBox_subtractFilteringMinPts->setValue(5);
616 _ui->checkBox_smoothing->setChecked(
false);
617 _ui->doubleSpinBox_mlsRadius->setValue(0.04);
618 _ui->spinBox_polygonialOrder->setValue(2);
619 _ui->comboBox_upsamplingMethod->setCurrentIndex(0);
620 _ui->doubleSpinBox_sampleRadius->setValue(0.01);
621 _ui->doubleSpinBox_sampleStep->setValue(0.005);
622 _ui->spinBox_randomPoints->setValue(10);
623 _ui->doubleSpinBox_dilationVoxelSize->setValue(0.005);
624 _ui->spinBox_dilationSteps->setValue(1);
625 _ui->doubleSpinBox_mls_outputVoxelSize->setValue(0);
627 _ui->checkBox_gainCompensation->setChecked(
false);
628 _ui->doubleSpinBox_gainRadius->setValue(0.02);
629 _ui->doubleSpinBox_gainOverlap->setValue(0.0);
630 _ui->doubleSpinBox_gainBeta->setValue(10);
631 _ui->checkBox_gainRGB->setChecked(
true);
632 _ui->checkBox_gainFull->setChecked(
false);
634 _ui->checkBox_meshing->setChecked(
false);
635 _ui->doubleSpinBox_gp3Radius->setValue(0.2);
636 _ui->doubleSpinBox_gp3Mu->setValue(2.5);
637 _ui->doubleSpinBox_meshDecimationFactor->setValue(0.0);
638 _ui->spinBox_meshMaxPolygons->setValue(0);
639 _ui->doubleSpinBox_transferColorRadius->setValue(0.025);
640 _ui->checkBox_cleanMesh->setChecked(
true);
641 _ui->spinBox_mesh_minClusterSize->setValue(0);
643 _ui->comboBox_meshingApproach->setCurrentIndex(1);
645 _ui->checkBox_textureMapping->setChecked(
false);
646 _ui->comboBox_meshingTextureFormat->setCurrentIndex(0);
647 _ui->comboBox_meshingTextureSize->setCurrentIndex(5);
648 _ui->spinBox_mesh_maxTextures->setValue(1);
649 _ui->doubleSpinBox_meshingTextureMaxDistance->setValue(3.0);
650 _ui->doubleSpinBox_meshingTextureMaxDepthError->setValue(0.0);
651 _ui->doubleSpinBox_meshingTextureMaxAngle->setValue(0.0);
652 _ui->spinBox_mesh_minTextureClusterSize->setValue(50);
653 _ui->lineEdit_meshingTextureRoiRatios->setText(
"0.0 0.0 0.0 0.0");
654 _ui->checkBox_distanceToCamPolicy->setChecked(
false);
655 _ui->checkBox_cameraFilter->setChecked(
false);
656 _ui->doubleSpinBox_cameraFilterRadius->setValue(0);
657 _ui->doubleSpinBox_cameraFilterAngle->setValue(30);
658 _ui->doubleSpinBox_cameraFilterVel->setValue(0);
659 _ui->doubleSpinBox_cameraFilterVelRad->setValue(0);
660 _ui->doubleSpinBox_laplacianVariance->setValue(0);
661 _ui->spinBox_textureBrightnessContrastRatioLow->setValue(0);
662 _ui->spinBox_textureBrightnessContrastRatioHigh->setValue(5);
663 _ui->checkBox_exposureFusion->setChecked(
false);
664 _ui->checkBox_blending->setChecked(
true);
665 _ui->comboBox_blendingDecimation->setCurrentIndex(0);
666 _ui->checkBox_multiband->setChecked(
false);
668 _ui->doubleSpinBox_mesh_angleTolerance->setValue(15.0);
669 _ui->checkBox_mesh_quad->setChecked(
false);
670 _ui->spinBox_mesh_triangleSize->setValue(1);
672 _ui->checkBox_poisson_outputPolygons->setChecked(
false);
673 _ui->checkBox_poisson_manifold->setChecked(
true);
674 _ui->spinBox_poisson_depth->setValue(0);
675 _ui->spinBox_poisson_iso->setValue(8);
676 _ui->spinBox_poisson_solver->setValue(8);
677 _ui->spinBox_poisson_minDepth->setValue(5);
678 _ui->doubleSpinBox_poisson_samples->setValue(1.0);
679 _ui->doubleSpinBox_poisson_pointWeight->setValue(4.0);
680 _ui->doubleSpinBox_poisson_scale->setValue(1.1);
682 _ui->doubleSpinBox_cputsdf_size->setValue(12.0);
683 _ui->doubleSpinBox_cputsdf_resolution->setValue(0.01);
684 _ui->doubleSpinBox_cputsdf_tuncPos->setValue(0.03);
685 _ui->doubleSpinBox_cputsdf_tuncNeg->setValue(0.03);
686 _ui->doubleSpinBox_cputsdf_minWeight->setValue(0);
687 _ui->doubleSpinBox_cputsdf_flattenRadius->setValue(0.005);
688 _ui->spinBox_cputsdf_randomSplit->setValue(1);
690 _ui->checkBox_openchisel_mergeVertices->setChecked(
true);
691 _ui->spinBox_openchisel_chunk_size_x->setValue(16);
692 _ui->spinBox_openchisel_chunk_size_y->setValue(16);
693 _ui->spinBox_openchisel_chunk_size_z->setValue(16);
694 _ui->doubleSpinBox_openchisel_truncation_constant->setValue(0.001504);
695 _ui->doubleSpinBox_openchisel_truncation_linear->setValue(0.00152);
696 _ui->doubleSpinBox_openchisel_truncation_quadratic->setValue(0.0019);
697 _ui->doubleSpinBox_openchisel_truncation_scale->setValue(10.0);
698 _ui->spinBox_openchisel_integration_weight->setValue(1);
699 _ui->checkBox_openchisel_use_voxel_carving->setChecked(
false);
700 _ui->doubleSpinBox_openchisel_carving_dist_m->setValue(0.05);
701 _ui->doubleSpinBox_openchisel_near_plane_dist->setValue(0.05);
702 _ui->doubleSpinBox_openchisel_far_plane_dist->setValue(1.1);
713 QString path = QFileDialog::getOpenFileName(
this, tr(
"Load Settings"),
_workingDirectory, tr(
"Config (*.ini)"));
716 QSettings settings(path, QSettings::IniFormat);
717 settings.beginGroup(
"Gui");
718 settings.beginGroup(this->objectName());
727 QString path = QFileDialog::getSaveFileName(
this, tr(
"Save Settings"),
_workingDirectory, tr(
"Config (*.ini)"));
730 QSettings settings(path, QSettings::IniFormat);
731 settings.beginGroup(
"Gui");
732 settings.beginGroup(this->objectName());
741 if(!
_ui->checkBox_fromDepth->isChecked())
743 _ui->comboBox_pipeline->setCurrentIndex(1);
744 _ui->comboBox_pipeline->setEnabled(
false);
745 _ui->comboBox_frame->setItemData(2, 0,Qt::UserRole - 1);
746 _ui->comboBox_frame->setItemData(3, 1|32,Qt::UserRole - 1);
747 if(
_ui->comboBox_frame->currentIndex() == 2)
749 _ui->comboBox_frame->setCurrentIndex(0);
754 _ui->comboBox_pipeline->setEnabled(
true);
755 _ui->comboBox_frame->setItemData(2, 1|32,Qt::UserRole - 1);
756 _ui->comboBox_frame->setItemData(3, 0,Qt::UserRole - 1);
757 if(
_ui->comboBox_frame->currentIndex() == 3)
759 _ui->comboBox_frame->setCurrentIndex(0);
762 _ui->comboBox_intensityColormap->setVisible(!
_ui->checkBox_fromDepth->isChecked() && !
_ui->checkBox_binary->isEnabled());
763 _ui->comboBox_intensityColormap->setEnabled(!
_ui->checkBox_fromDepth->isChecked() && !
_ui->checkBox_binary->isEnabled());
764 _ui->label_intensityColormap->setVisible(!
_ui->checkBox_fromDepth->isChecked() && !
_ui->checkBox_binary->isEnabled());
766 _ui->checkBox_smoothing->setVisible(
_ui->comboBox_pipeline->currentIndex() == 1);
767 _ui->checkBox_smoothing->setEnabled(
_ui->comboBox_pipeline->currentIndex() == 1);
768 _ui->label_smoothing->setVisible(
_ui->comboBox_pipeline->currentIndex() == 1);
770 _ui->comboBox_frame->setEnabled(!
_ui->checkBox_assemble->isChecked() &&
_ui->checkBox_binary->isEnabled());
771 _ui->comboBox_frame->setVisible(
_ui->comboBox_frame->isEnabled());
772 _ui->label_frame->setVisible(
_ui->comboBox_frame->isEnabled());
773 _ui->checkBox_gainCompensation->setEnabled(!(
_ui->comboBox_frame->isEnabled() &&
_ui->comboBox_frame->currentIndex() == 2));
774 _ui->checkBox_gainCompensation->setVisible(
_ui->checkBox_gainCompensation->isEnabled());
775 _ui->label_gainCompensation->setVisible(
_ui->checkBox_gainCompensation->isEnabled());
777 _ui->groupBox_regenerate->setVisible(
_ui->checkBox_regenerate->isChecked() &&
_ui->checkBox_fromDepth->isChecked());
778 _ui->groupBox_regenerateScans->setVisible(
_ui->checkBox_regenerate->isChecked() && !
_ui->checkBox_fromDepth->isChecked());
779 _ui->groupBox_bilateral->setVisible(
_ui->checkBox_bilateral->isChecked());
780 _ui->groupBox_filtering->setVisible(
_ui->checkBox_filtering->isChecked());
781 _ui->groupBox_gain->setVisible(
_ui->checkBox_gainCompensation->isEnabled() &&
_ui->checkBox_gainCompensation->isChecked());
782 _ui->groupBox_mls->setVisible(
_ui->checkBox_smoothing->isEnabled() &&
_ui->checkBox_smoothing->isChecked());
783 _ui->groupBox_meshing->setVisible(
_ui->checkBox_meshing->isChecked());
784 _ui->groupBox_subtraction->setVisible(
_ui->checkBox_subtraction->isChecked());
785 _ui->groupBox_textureMapping->setVisible(
_ui->checkBox_textureMapping->isChecked());
786 _ui->groupBox_cameraFilter->setVisible(
_ui->checkBox_cameraFilter->isChecked());
789 if(
_ui->checkBox_meshing->isChecked())
792 _ui->comboBox_meshingApproach->setItemData(0,
_ui->comboBox_pipeline->currentIndex() == 1?1 | 32:0,Qt::UserRole - 1);
795 _ui->comboBox_meshingApproach->setItemData(1,
_ui->comboBox_pipeline->currentIndex() == 1 &&
_ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
798 #ifdef RTABMAP_CPUTSDF 799 _ui->comboBox_meshingApproach->setItemData(2,
_ui->comboBox_pipeline->currentIndex() == 0 &&
_ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
801 _ui->comboBox_meshingApproach->setItemData(2, 0, Qt::UserRole - 1);
805 _ui->comboBox_meshingApproach->setItemData(3,
_ui->comboBox_pipeline->currentIndex() == 0?1 | 32:0,Qt::UserRole - 1);
808 #ifdef RTABMAP_OPENCHISEL 809 _ui->comboBox_meshingApproach->setItemData(4,
_ui->checkBox_assemble->isChecked()?1 | 32:0,Qt::UserRole - 1);
811 _ui->comboBox_meshingApproach->setItemData(4, 0, Qt::UserRole - 1);
814 if(
_ui->comboBox_pipeline->currentIndex() == 0 &&
_ui->comboBox_meshingApproach->currentIndex()<2)
816 _ui->comboBox_meshingApproach->setCurrentIndex(3);
818 if(
_ui->comboBox_pipeline->currentIndex() == 1 && (
_ui->comboBox_meshingApproach->currentIndex()==2 ||
_ui->comboBox_meshingApproach->currentIndex()==3))
820 _ui->comboBox_meshingApproach->setCurrentIndex(1);
822 if(!
_ui->checkBox_assemble->isChecked())
824 _ui->comboBox_meshingApproach->setCurrentIndex(
_ui->comboBox_pipeline->currentIndex() == 1?0:3);
827 _ui->checkBox_poisson_outputPolygons->setDisabled(
828 _ui->checkBox_binary->isEnabled() ||
829 _ui->doubleSpinBox_meshDecimationFactor->value()!=0.0 ||
830 _ui->spinBox_meshMaxPolygons->value()!=0 ||
831 _ui->checkBox_textureMapping->isChecked());
832 _ui->label_outputPolygons->setEnabled(
_ui->checkBox_poisson_outputPolygons->isEnabled());
834 _ui->checkBox_cleanMesh->setEnabled(
_ui->comboBox_pipeline->currentIndex() == 1);
835 _ui->label_meshClean->setEnabled(
_ui->comboBox_pipeline->currentIndex() == 1);
837 _ui->groupBox_gp3->setVisible(
_ui->comboBox_pipeline->currentIndex() == 1 &&
_ui->comboBox_meshingApproach->currentIndex()==0);
838 _ui->groupBox_poisson->setVisible(
_ui->comboBox_pipeline->currentIndex() == 1 &&
_ui->comboBox_meshingApproach->currentIndex()==1);
839 _ui->groupBox_cputsdf->setVisible(
_ui->comboBox_pipeline->currentIndex() == 0 &&
_ui->comboBox_meshingApproach->currentIndex()==2);
840 _ui->groupBox_organized->setVisible(
_ui->comboBox_pipeline->currentIndex() == 0 &&
_ui->comboBox_meshingApproach->currentIndex()==3);
841 _ui->groupBox_openchisel->setVisible(
_ui->comboBox_meshingApproach->currentIndex()==4);
844 _ui->doubleSpinBox_meshDecimationFactor->setEnabled(
_ui->comboBox_meshingApproach->currentIndex()!=3);
845 _ui->label_meshDecimation->setEnabled(
_ui->comboBox_meshingApproach->currentIndex()!=3);
846 _ui->spinBox_meshMaxPolygons->setEnabled(
_ui->comboBox_meshingApproach->currentIndex()!=3);
847 _ui->label_meshMaxPolygons->setEnabled(
_ui->comboBox_meshingApproach->currentIndex()!=3);
850 #ifndef RTABMAP_ALICE_VISION 851 _ui->checkBox_multiband->setEnabled(
false);
853 _ui->checkBox_multiband->setEnabled(
_ui->checkBox_binary->isEnabled());
855 _ui->label_multiband->setEnabled(
_ui->checkBox_multiband->isEnabled());
861 QString dir =
_ui->lineEdit_distortionModel->text();
866 QString path = QFileDialog::getOpenFileName(
this, tr(
"Select file"), dir, tr(
"Distortion model (*.bin *.txt)"));
869 _ui->lineEdit_distortionModel->setText(path);
875 _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(
false);
876 _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(
true);
877 _ui->checkBox_binary->setVisible(
true);
878 _ui->checkBox_binary->setEnabled(
true);
879 _ui->label_binaryFile->setVisible(
true);
880 _ui->checkBox_mesh_quad->setVisible(
false);
881 _ui->checkBox_mesh_quad->setEnabled(
false);
882 _ui->label_quad->setVisible(
false);
888 _ui->buttonBox->button(QDialogButtonBox::Ok)->setVisible(
true);
889 _ui->buttonBox->button(QDialogButtonBox::Save)->setVisible(
false);
890 _ui->checkBox_binary->setVisible(
false);
891 _ui->checkBox_binary->setEnabled(
false);
892 _ui->label_binaryFile->setVisible(
false);
893 _ui->checkBox_mesh_quad->setVisible(
true);
894 _ui->checkBox_mesh_quad->setEnabled(
true);
895 _ui->label_quad->setVisible(
true);
900 const std::map<int, Transform> & poses,
901 const std::multimap<int, Link> & links,
902 const std::map<int, int> & mapIds,
903 const QMap<int, Signature> & cachedSignatures,
904 const std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
905 const std::map<int, LaserScan> & cachedScans,
906 const QString & workingDirectory,
909 std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
910 std::map<int, pcl::PolygonMesh::Ptr> meshes;
911 std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
912 std::vector<std::map<int, pcl::PointXY> > textureVertexToPixels;
928 textureVertexToPixels))
930 if(textureMeshes.size())
932 saveTextureMeshes(workingDirectory, poses, textureMeshes, cachedSignatures, textureVertexToPixels);
934 else if(meshes.size())
936 bool exportMeshes =
true;
937 if(
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked())
939 QMessageBox::StandardButton r = QMessageBox::warning(
this, tr(
"Exporting Texture Mesh"),
940 tr(
"No texture mesh could be created, do you want to continue with saving only the meshes (%1)?").arg(meshes.size()),
941 QMessageBox::Yes|QMessageBox::No, QMessageBox::Yes);
942 exportMeshes = r == QMessageBox::Yes;
946 saveMeshes(workingDirectory, poses, meshes,
_ui->checkBox_binary->isChecked());
951 saveClouds(workingDirectory, poses, clouds,
_ui->checkBox_binary->isChecked());
962 const std::map<int, Transform> & poses,
963 const std::multimap<int, Link> & links,
964 const std::map<int, int> & mapIds,
965 const QMap<int, Signature> & cachedSignatures,
966 const std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
967 const std::map<int, LaserScan> & cachedScans,
968 const QString & workingDirectory,
971 std::map<int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> clouds;
972 std::map<int, pcl::PolygonMesh::Ptr> meshes;
973 std::map<int, pcl::TextureMesh::Ptr> textureMeshes;
974 std::vector<std::map<int, pcl::PointXY> > textureVertexToPixels;
990 textureVertexToPixels))
992 QDialog * window =
new QDialog(this->parentWidget()?this->parentWidget():
this, Qt::Window);
993 window->setAttribute(Qt::WA_DeleteOnClose,
true);
996 window->setWindowTitle(tr(
"Meshes (%1 nodes)").arg(meshes.size()));
1000 window->setWindowTitle(tr(
"Clouds (%1 nodes)").arg(clouds.size()));
1002 window->setMinimumWidth(120);
1003 window->setMinimumHeight(90);
1004 window->resize(QDesktopWidget().availableGeometry(
this).size() * 0.7);
1007 if(
_ui->comboBox_pipeline->currentIndex() == 0)
1014 if(
_ui->comboBox_intensityColormap->currentIndex()==1)
1018 else if(
_ui->comboBox_intensityColormap->currentIndex() == 2)
1023 QVBoxLayout *layout =
new QVBoxLayout();
1024 layout->addWidget(viewer);
1025 layout->setContentsMargins(0,0,0,0);
1026 window->setLayout(layout);
1027 connect(window, SIGNAL(finished(
int)), viewer, SLOT(clear()));
1032 QApplication::processEvents();
1034 QApplication::processEvents();
1036 if(textureMeshes.size())
1039 std::map<int, cv::Mat> images;
1040 std::map<int, std::vector<CameraModel> > calibrations;
1041 for(QMap<int, Signature>::const_iterator iter=cachedSignatures.constBegin(); iter!=cachedSignatures.constEnd(); ++iter)
1043 std::vector<CameraModel> models;
1044 if(iter->sensorData().cameraModels().size())
1046 models = iter->sensorData().cameraModels();
1048 else if(iter->sensorData().stereoCameraModel().isValidForProjection())
1050 models.push_back(iter->sensorData().stereoCameraModel().left());
1055 if(!iter->sensorData().imageRaw().empty())
1057 calibrations.insert(std::make_pair(iter.key(), models));
1058 images.insert(std::make_pair(iter.key(), iter->sensorData().imageRaw()));
1060 else if(!iter->sensorData().imageCompressed().empty())
1062 calibrations.insert(std::make_pair(iter.key(), models));
1063 images.insert(std::make_pair(iter.key(), iter->sensorData().imageCompressed()));
1067 int textureSize = 1024;
1068 if(
_ui->comboBox_meshingTextureSize->currentIndex() > 0)
1070 textureSize = 128 <<
_ui->comboBox_meshingTextureSize->currentIndex();
1072 int blendingDecimation = 0;
1073 if(
_ui->checkBox_blending->isChecked())
1075 if(
_ui->comboBox_blendingDecimation->currentIndex() > 0)
1077 blendingDecimation = 1 << (
_ui->comboBox_blendingDecimation->currentIndex()-1);
1081 for (std::map<int, pcl::TextureMesh::Ptr>::iterator iter = textureMeshes.begin(); iter != textureMeshes.end(); ++iter)
1083 pcl::TextureMesh::Ptr mesh = iter->second;
1086 cv::Mat globalTexture;
1087 if (mesh->tex_materials.size() > 1)
1089 cv::Mat globalTextures;
1098 textureVertexToPixels,
1099 _ui->checkBox_gainCompensation->isChecked(),
1100 _ui->doubleSpinBox_gainBeta->value(),
1101 _ui->checkBox_gainRGB->isChecked(),
1102 _ui->checkBox_blending->isChecked(),
1104 _ui->spinBox_textureBrightnessContrastRatioLow->value(),
1105 _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
1106 _ui->checkBox_exposureFusion->isEnabled() &&
_ui->checkBox_exposureFusion->isChecked());
1107 if(globalTextures.rows == globalTextures.cols)
1109 globalTexture = globalTextures;
1113 _progressDialog->
appendText(tr(
"Viewing the mesh %1 (%2 polygons)...").arg(iter->first).arg(mesh->tex_polygons.size()?mesh->tex_polygons[0].size():0));
1120 for (
unsigned int t = 0; t < mesh->tex_coordinates.size(); ++t)
1122 if(mesh->tex_polygons[t].size())
1125 pcl::PointCloud<pcl::PointXYZ>::Ptr originalCloud(
new pcl::PointCloud<pcl::PointXYZ>);
1126 pcl::fromPCLPointCloud2(mesh->cloud, *originalCloud);
1129 unsigned int nPoints = mesh->tex_coordinates[t].size();
1130 UASSERT(nPoints == mesh->tex_polygons[t].size()*mesh->tex_polygons[t][0].vertices.size());
1132 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZ>);
1133 cloud->resize(nPoints);
1135 unsigned int oi = 0;
1136 for (
unsigned int i = 0; i < mesh->tex_polygons[t].size(); ++i)
1138 pcl::Vertices &
vertices = mesh->tex_polygons[t][i];
1140 for(
unsigned int j=0; j<vertices.vertices.size(); ++j)
1143 UASSERT_MSG(vertices.vertices[j] < originalCloud->size(),
uFormat(
"%d vs %d", vertices.vertices[j], (
int)originalCloud->size()).c_str());
1144 cloud->at(oi) = originalCloud->at(vertices.vertices[j]);
1145 vertices.vertices[j] = oi;
1149 pcl::toPCLPointCloud2(*cloud, mesh->cloud);
1153 UWARN(
"No polygons for texture %d of mesh %d?!", t, iter->first);
1157 if (globalTexture.empty())
1159 if(mesh->tex_materials.size()==1 &&
1160 !mesh->tex_materials[0].tex_file.empty() &&
1161 uIsInteger(mesh->tex_materials[0].tex_file,
false))
1163 int textureId =
uStr2Int(mesh->tex_materials[0].tex_file);
1165 if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
1167 data = cachedSignatures.value(textureId).sensorData();
1175 UASSERT(!globalTexture.empty());
1189 _progressDialog->
appendText(tr(
"Viewing the mesh %1 (%2 polygons)... done.").arg(iter->first).arg(mesh->tex_polygons.size()?mesh->tex_polygons[0].size():0));
1190 QApplication::processEvents();
1193 else if(meshes.size())
1196 viewer->
setLighting(
_ui->doubleSpinBox_transferColorRadius->value() < 0.0);
1197 for(std::map<int, pcl::PolygonMesh::Ptr>::iterator iter = meshes.begin(); iter!=meshes.end(); ++iter)
1199 _progressDialog->
appendText(tr(
"Viewing the mesh %1 (%2 polygons)...").arg(iter->first).arg(iter->second->polygons.size()));
1202 for(
unsigned int i=0; i<iter->second->cloud.fields.size(); ++i)
1204 if(iter->second->cloud.fields[i].name.compare(
"rgb") == 0)
1212 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
1213 pcl::fromPCLPointCloud2(iter->second->cloud, *cloud);
1218 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZ>);
1219 pcl::fromPCLPointCloud2(iter->second->cloud, *cloud);
1222 _progressDialog->
appendText(tr(
"Viewing the mesh %1 (%2 polygons)... done.").arg(iter->first).arg(iter->second->polygons.size()));
1223 QApplication::processEvents();
1226 else if(clouds.size())
1228 for(std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::iterator iter = clouds.begin(); iter!=clouds.end(); ++iter)
1233 QColor color = Qt::gray;
1234 int mapId =
uValue(mapIds, iter->first, -1);
1237 color = (Qt::GlobalColor)(mapId % 12 + 7 );
1240 if(!
_ui->checkBox_fromDepth->isChecked())
1243 if(
_ui->spinBox_normalKSearch->value()<=0 &&
_ui->doubleSpinBox_normalRadiusSearch->value()<=0.0)
1246 pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIWithoutNormals(
new pcl::PointCloud<pcl::PointXYZI>);
1247 cloudIWithoutNormals->resize(iter->second->size());
1248 for(
unsigned int i=0; i<cloudIWithoutNormals->size(); ++i)
1250 cloudIWithoutNormals->points[i].x = iter->second->points[i].x;
1251 cloudIWithoutNormals->points[i].y = iter->second->points[i].y;
1252 cloudIWithoutNormals->points[i].z = iter->second->points[i].z;
1253 int * intensity = (
int *)&cloudIWithoutNormals->points[i].intensity;
1255 int(iter->second->points[i].r) |
1256 int(iter->second->points[i].g) << 8 |
1257 int(iter->second->points[i].b) << 16 |
1258 int(iter->second->points[i].a) << 24;
1264 pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloudI(
new pcl::PointCloud<pcl::PointXYZINormal>);
1265 cloudI->resize(iter->second->size());
1266 for(
unsigned int i=0; i<cloudI->size(); ++i)
1268 cloudI->points[i].x = iter->second->points[i].x;
1269 cloudI->points[i].y = iter->second->points[i].y;
1270 cloudI->points[i].z = iter->second->points[i].z;
1271 cloudI->points[i].normal_x = iter->second->points[i].normal_x;
1272 cloudI->points[i].normal_y = iter->second->points[i].normal_y;
1273 cloudI->points[i].normal_z = iter->second->points[i].normal_z;
1274 cloudI->points[i].curvature = iter->second->points[i].curvature;
1275 int * intensity = (
int *)&cloudI->points[i].intensity;
1277 int(iter->second->points[i].r) |
1278 int(iter->second->points[i].g) << 8 |
1279 int(iter->second->points[i].b) << 16 |
1280 int(iter->second->points[i].a) << 24;
1291 _progressDialog->
appendText(tr(
"Viewing the cloud %1 (%2 points)... done.").arg(iter->first).arg(iter->second->size()));
1305 int textureSize = 1024;
1306 if(
_ui->comboBox_meshingTextureSize->currentIndex() > 0)
1308 textureSize = 128 <<
_ui->comboBox_meshingTextureSize->currentIndex();
1314 return _ui->spinBox_mesh_maxTextures->value();
1318 return _ui->checkBox_gainCompensation->isChecked();
1322 return _ui->doubleSpinBox_gainBeta->value();
1326 return _ui->checkBox_gainRGB->isChecked();
1330 return _ui->checkBox_blending->isChecked();
1334 int blendingDecimation = 0;
1335 if(
_ui->checkBox_blending->isChecked())
1337 if(
_ui->comboBox_blendingDecimation->currentIndex() > 0)
1339 blendingDecimation = 1 << (
_ui->comboBox_blendingDecimation->currentIndex()-1);
1342 return blendingDecimation;
1346 return _ui->spinBox_textureBrightnessContrastRatioLow->value();
1350 return _ui->spinBox_textureBrightnessContrastRatioHigh->value();
1354 return _ui->checkBox_exposureFusion->isEnabled() &&
_ui->checkBox_exposureFusion->isChecked();
1362 if (dir.exists(dirName)) {
1363 Q_FOREACH(QFileInfo info, dir.entryInfoList(QDir::NoDotAndDotDot | QDir::System | QDir::Hidden | QDir::AllDirs | QDir::Files, QDir::DirsFirst)) {
1368 result = QFile::remove(info.absoluteFilePath());
1375 result = dir.rmdir(dirName);
1381 const std::map<int, Transform> & poses,
1382 const std::multimap<int, Link> & links,
1383 const std::map<int, int> & mapIds,
1384 const QMap<int, Signature> & cachedSignatures,
1385 const std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
1386 const std::map<int, LaserScan> & cachedScans,
1387 const QString & workingDirectory,
1389 std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & cloudsWithNormals,
1390 std::map<int, pcl::PolygonMesh::Ptr> & meshes,
1391 std::map<int, pcl::TextureMesh::Ptr> & textureMeshes,
1392 std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels)
1396 _ui->checkBox_regenerate->setEnabled(
true);
1397 if(cachedSignatures.empty() &&
_dbDriver)
1399 _ui->checkBox_regenerate->setChecked(
true);
1400 _ui->checkBox_regenerate->setEnabled(
false);
1407 if(this->exec() == QDialog::Accepted)
1411 QMessageBox::critical(
this, tr(
"Creating clouds..."), tr(
"Poses are null! Cannot export/view clouds."));
1417 if(
_ui->checkBox_meshing->isChecked())
1421 if(
_ui->checkBox_assemble->isChecked())
1426 if(
_ui->checkBox_subtraction->isChecked())
1430 if(
_ui->checkBox_textureMapping->isChecked())
1434 if(
_ui->checkBox_gainCompensation->isChecked())
1438 if(
_ui->checkBox_mesh_quad->isEnabled())
1444 bool loadClouds =
true;
1445 #ifdef RTABMAP_OPENCHISEL 1446 if(
_ui->comboBox_meshingApproach->currentIndex()==4 &&
_ui->checkBox_assemble->isChecked())
1448 loadClouds = !
_ui->checkBox_fromDepth->isChecked();
1452 bool has2dScans =
false;
1453 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
1467 for(std::map<int, Transform>::const_iterator iter=poses.begin(); iter!=poses.end(); ++iter)
1469 clouds.insert(std::make_pair(iter->first,
1471 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr(
new pcl::PointCloud<pcl::PointXYZRGBNormal>),
1472 pcl::IndicesPtr(
new std::vector<int>))));
1477 std::set<int> validCameras =
uKeysSet(clouds);
1488 if(
_ui->checkBox_regenerate->isEnabled() && !
_ui->checkBox_regenerate->isChecked())
1490 QMessageBox::warning(
this, tr(
"Creating clouds..."), tr(
"Could create clouds for %1 node(s). You " 1491 "may want to activate clouds regeneration option.").arg(poses.size()));
1495 QMessageBox::warning(
this, tr(
"Creating clouds..."), tr(
"Could not create clouds for %1 " 1496 "node(s). The cache may not contain point cloud data. Try re-downloading the map.").arg(poses.size()));
1502 if(
_ui->checkBox_gainCompensation->isChecked() &&
_ui->checkBox_fromDepth->isChecked() && clouds.size() > 1 &&
1504 !(
_ui->checkBox_meshing->isChecked() &&
1505 _ui->checkBox_textureMapping->isEnabled() &&
1506 _ui->checkBox_textureMapping->isChecked() &&
1507 _ui->comboBox_pipeline->currentIndex()==1 &&
1508 _ui->checkBox_assemble->isChecked() &&
1509 _ui->comboBox_meshingTextureSize->isEnabled() &&
1510 _ui->comboBox_meshingTextureSize->currentIndex() > 0) &&
1512 !(
_ui->comboBox_frame->isEnabled() &&
_ui->comboBox_frame->currentIndex()==2))
1517 if(
_ui->checkBox_gainFull->isChecked())
1525 QApplication::processEvents();
1527 QApplication::processEvents();
1529 if(
_ui->checkBox_gainFull->isChecked())
1531 std::multimap<int, Link> allLinks;
1532 for(std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator iter=clouds.begin(); iter!=clouds.end(); ++iter)
1534 int from = iter->first;
1535 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::const_iterator jter = iter;
1537 for(;jter!=clouds.end(); ++jter)
1539 int to = jter->first;
1540 allLinks.insert(std::make_pair(from,
Link(from, to,
Link::kUserClosure, poses.at(from).inverse()*poses.at(to))));
1551 if(!(
_ui->checkBox_meshing->isChecked() &&
1552 _ui->checkBox_textureMapping->isEnabled() &&
1553 _ui->checkBox_textureMapping->isChecked()))
1556 for(std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator jter=clouds.begin();jter!=clouds.end(); ++jter)
1558 if(jter!=clouds.end())
1561 _compensator->
apply(jter->first, jter->second.first, jter->second.second,
_ui->checkBox_gainRGB->isChecked());
1565 QApplication::processEvents();
1576 std::map<int, Transform> normalViewpoints = poses;
1577 if(
_ui->checkBox_assemble->isChecked())
1580 for(std::map<int, Transform>::iterator iter= normalViewpoints.begin(); iter!=normalViewpoints.end(); ++iter)
1582 if(
_ui->checkBox_fromDepth->isChecked())
1584 std::vector<CameraModel> models;
1586 if(cachedSignatures.contains(iter->first))
1588 const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
1597 if(models.size() && !models[0].localTransform().isNull())
1599 iter->second *= models[0].localTransform();
1610 iter->second *= cachedScans.at(iter->first).localTransform();
1612 else if(cachedSignatures.contains(iter->first))
1614 const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
1635 pcl::PointCloud<pcl::PointXYZ>::Ptr rawAssembledCloud(
new pcl::PointCloud<pcl::PointXYZ>);
1636 std::vector<int> rawCameraIndices;
1637 if(
_ui->checkBox_assemble->isChecked() &&
1638 !((
_ui->comboBox_pipeline->currentIndex()==0 ||
_ui->comboBox_meshingApproach->currentIndex()==4) &&
_ui->checkBox_meshing->isChecked()))
1641 QApplication::processEvents();
1644 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr assembledCloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1645 for(std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator iter=clouds.begin();
1646 iter!= clouds.end();
1649 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformed(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1650 if(iter->second.first->isOrganized())
1652 pcl::copyPointCloud(*iter->second.first, *iter->second.second, *transformed);
1659 pcl::copyPointCloud(*iter->second.first, *iter->second.second, *transformed);
1663 *assembledCloud += *transformed;
1664 rawCameraIndices.resize(assembledCloud->size(), iter->first);
1666 _progressDialog->
appendText(tr(
"Assembled cloud %1, total=%2 (%3/%4).").arg(iter->first).arg(assembledCloud->size()).arg(++i).arg(clouds.size()));
1668 QApplication::processEvents();
1675 assembledCloud->is_dense =
true;
1676 if(
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
1678 pcl::copyPointCloud(*assembledCloud, *rawAssembledCloud);
1681 if(
_ui->doubleSpinBox_voxelSize_assembled->value())
1684 .arg(assembledCloud->size())
1685 .arg(
_ui->doubleSpinBox_voxelSize_assembled->value()));
1686 QApplication::processEvents();
1687 unsigned int before = assembledCloud->size();
1690 _ui->doubleSpinBox_voxelSize_assembled->value());
1693 .arg(
_ui->doubleSpinBox_voxelSize_assembled->value())
1694 .arg(assembledCloud->size()));
1698 pcl::IndicesPtr indices(
new std::vector<int>);
1699 indices->resize(assembledCloud->size());
1700 for(
unsigned int i=0; i<indices->size(); ++i)
1705 if(!
_ui->checkBox_fromDepth->isChecked() && !has2dScans &&
1706 (
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0))
1709 pcl::PointCloud<pcl::PointXYZ>::Ptr cloudWithoutNormals(
new pcl::PointCloud<pcl::PointXYZ>);
1710 pcl::copyPointCloud(*assembledCloud, *cloudWithoutNormals);
1711 pcl::PointCloud<pcl::Normal>::Ptr normals =
util3d::computeNormals(cloudWithoutNormals, indices,
_ui->spinBox_normalKSearch->value(),
_ui->doubleSpinBox_normalRadiusSearch->value());
1713 UASSERT(assembledCloud->size() == normals->size());
1714 for(
unsigned int i=0; i<normals->size(); ++i)
1716 assembledCloud->points[i].normal_x = normals->points[i].normal_x;
1717 assembledCloud->points[i].normal_y = normals->points[i].normal_y;
1718 assembledCloud->points[i].normal_z = normals->points[i].normal_z;
1729 clouds.insert(std::make_pair(0, std::make_pair(assembledCloud, indices)));
1738 if(
_ui->checkBox_smoothing->isEnabled() &&
_ui->checkBox_smoothing->isChecked() && !has2dScans)
1741 "[search radius=%1m voxel=%2m]").arg(
_ui->doubleSpinBox_mlsRadius->value()).arg(
_ui->doubleSpinBox_voxelSize_assembled->value()));
1742 QApplication::processEvents();
1744 QApplication::processEvents();
1748 for(std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> >::iterator iter=clouds.begin();
1749 iter!= clouds.end();)
1751 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudWithNormals = iter->second.first;
1753 if(
_ui->checkBox_smoothing->isEnabled() &&
_ui->checkBox_smoothing->isChecked() && !has2dScans)
1755 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals(
new pcl::PointCloud<pcl::PointXYZRGB>);
1756 if(iter->second.second->size())
1758 pcl::copyPointCloud(*cloudWithNormals, *iter->second.second, *cloudWithoutNormals);
1762 pcl::copyPointCloud(*cloudWithNormals, *cloudWithoutNormals);
1766 QApplication::processEvents();
1768 QApplication::processEvents();
1775 cloudWithoutNormals,
1776 (
float)
_ui->doubleSpinBox_mlsRadius->value(),
1777 _ui->spinBox_polygonialOrder->value(),
1778 _ui->comboBox_upsamplingMethod->currentIndex(),
1779 (float)
_ui->doubleSpinBox_sampleRadius->value(),
1780 (float)
_ui->doubleSpinBox_sampleStep->value(),
1781 _ui->spinBox_randomPoints->value(),
1782 (float)
_ui->doubleSpinBox_dilationVoxelSize->value(),
1783 _ui->spinBox_dilationSteps->value());
1786 UDEBUG(
"NaNs filtering... size before = %d", cloudWithNormals->size());
1788 UDEBUG(
"NaNs filtering... size after = %d", cloudWithNormals->size());
1790 if(
_ui->checkBox_assemble->isChecked())
1793 if(
_ui->doubleSpinBox_mls_outputVoxelSize->value())
1796 .arg(cloudWithNormals->size())
1797 .arg(
_ui->doubleSpinBox_mls_outputVoxelSize->value()));
1798 QApplication::processEvents();
1802 _ui->doubleSpinBox_mls_outputVoxelSize->value());
1805 _progressDialog->
appendText(tr(
"Update %1 normals with %2 camera views...").arg(cloudWithNormals->size()).arg(poses.size()));
1814 else if(iter->second.first->isOrganized() &&
_ui->checkBox_filtering->isChecked())
1819 cloudsWithNormals.insert(std::make_pair(iter->first, cloudWithNormals));
1822 clouds.erase(iter++);
1825 QApplication::processEvents();
1833 #ifdef RTABMAP_CPUTSDF 1834 cpu_tsdf::TSDFVolumeOctree::Ptr tsdf;
1836 #ifdef RTABMAP_OPENCHISEL 1837 chisel::ChiselPtr chiselMap;
1838 chisel::ProjectionIntegrator projectionIntegrator;
1842 std::map<int, std::vector<int> > organizedIndices;
1843 std::map<int, cv::Size> organizedCloudSizes;
1846 UDEBUG(
"Meshing=%d",
_ui->checkBox_meshing->isChecked()?1:0);
1847 if(
_ui->checkBox_meshing->isChecked() && !has2dScans)
1850 #ifdef RTABMAP_OPENCHISEL 1851 if(
_ui->comboBox_meshingApproach->currentIndex()==4 &&
_ui->checkBox_assemble->isChecked())
1855 QApplication::processEvents();
1857 QApplication::processEvents();
1859 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
1860 std::vector<pcl::Vertices> mergedPolygons;
1862 int cloudsAdded = 1;
1863 for(std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::iterator iter=cloudsWithNormals.begin();
1864 iter!= cloudsWithNormals.end();
1865 ++iter,++cloudsAdded)
1867 std::vector<CameraModel> models;
1869 bool cacheHasCompressedImage =
false;
1871 if(cachedSignatures.contains(iter->first))
1873 const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
1884 if(chiselMap.get() == 0)
1887 int chunkSizeX =
_ui->spinBox_openchisel_chunk_size_x->value();
1888 int chunkSizeY =
_ui->spinBox_openchisel_chunk_size_y->value();
1889 int chunkSizeZ =
_ui->spinBox_openchisel_chunk_size_z->value();
1890 float voxelResolution =
_ui->doubleSpinBox_voxelSize_assembled->value();
1891 if(voxelResolution <=0.0
f)
1897 bool useColor =
_ui->checkBox_fromDepth->isChecked();
1898 chiselMap.reset(
new chisel::Chisel(Eigen::Vector3i(chunkSizeX, chunkSizeY, chunkSizeZ), voxelResolution, useColor));
1899 double truncationDistConst =
_ui->doubleSpinBox_openchisel_truncation_constant->value();
1900 double truncationDistLinear =
_ui->doubleSpinBox_openchisel_truncation_linear->value();
1901 double truncationDistQuad =
_ui->doubleSpinBox_openchisel_truncation_quadratic->value();
1902 double truncationDistScale =
_ui->doubleSpinBox_openchisel_truncation_scale->value();
1903 int weight =
_ui->spinBox_openchisel_integration_weight->value();
1904 bool useCarving =
_ui->checkBox_openchisel_use_voxel_carving->isChecked();
1905 double carvingDist =
_ui->doubleSpinBox_openchisel_carving_dist_m->value();
1906 chisel::Vec4 truncation(truncationDistQuad, truncationDistLinear, truncationDistConst, truncationDistScale);
1907 UDEBUG(
"If crashing just after this message, make sure PCL and OpenChisel are built both with -march=native or both without -march=native");
1908 projectionIntegrator.SetCentroids(chiselMap->GetChunkManager().GetCentroids());
1909 projectionIntegrator.SetTruncator(chisel::TruncatorPtr(
new chisel::QuadraticTruncator(truncation(0), truncation(1), truncation(2), truncation(3))));
1910 projectionIntegrator.SetWeighter(chisel::WeighterPtr(
new chisel::ConstantWeighter(weight)));
1911 projectionIntegrator.SetCarvingDist(carvingDist);
1912 projectionIntegrator.SetCarvingEnabled(useCarving);
1916 double nearPlaneDist =
_ui->doubleSpinBox_openchisel_near_plane_dist->value();
1917 double farPlaneDist =
_ui->doubleSpinBox_openchisel_far_plane_dist->value();
1918 if(
_ui->checkBox_fromDepth->isChecked())
1920 if(models.size() == 1 && !models[0].localTransform().isNull())
1925 if(cacheHasCompressedImage)
1927 cachedSignatures.find(iter->first)->sensorData().uncompressDataConst(&rgb, &depth);
1935 if(!rgb.empty() && !depth.empty())
1939 if(rgb.cols > depth.cols)
1941 UASSERT(rgb.cols % depth.cols == 0);
1942 depthModel = depthModel.
scaled(
double(depth.cols)/
double(rgb.cols));
1945 if(depth.type() == CV_16UC1)
1950 std::shared_ptr<chisel::ColorImage<unsigned char> > colorChisel =
colorImageToChisel(rgb);
1955 cameraColor.SetNearPlane(nearPlaneDist);
1956 cameraColor.SetFarPlane(farPlaneDist);
1957 cameraDepth.SetNearPlane(nearPlaneDist);
1958 cameraDepth.SetFarPlane(farPlaneDist);
1960 chisel::Transform pose_rel_to_first_frame = (poses.at(iter->first)*models[0].localTransform()).toEigen3f();
1961 chiselMap->IntegrateDepthScanColor<float,
unsigned char>(projectionIntegrator, depthChisel, pose_rel_to_first_frame, cameraDepth, colorChisel, pose_rel_to_first_frame, cameraColor);
1971 _progressDialog->
appendText(tr(
"OpenChisel: Invalid camera model for cloud %1! Only single RGB-D camera supported.").arg(iter->first), Qt::darkYellow);
1979 chisel::Transform pose_rel_to_first_frame = (poses.at(iter->first)*scanInfo.
localTransform()).toEigen3f();
1980 chiselMap->IntegratePointCloud(projectionIntegrator, *chiselCloud, pose_rel_to_first_frame, farPlaneDist);
1989 chiselMap->UpdateMeshes();
1991 _progressDialog->
appendText(tr(
"OpenChisel: Integrated cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
1994 QApplication::processEvents();
2004 if(
_ui->comboBox_pipeline->currentIndex() == 0)
2006 if(
_ui->comboBox_meshingApproach->currentIndex()==2)
2014 QApplication::processEvents();
2016 QApplication::processEvents();
2018 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2019 std::vector<pcl::Vertices> mergedPolygons;
2021 int cloudsAdded = 1;
2022 for(std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::iterator iter=cloudsWithNormals.begin();
2023 iter!= cloudsWithNormals.end();
2024 ++iter,++cloudsAdded)
2026 if(iter->second->isOrganized())
2028 if(iter->second->size())
2030 Eigen::Vector3f viewpoint(0.0
f,0.0
f,0.0
f);
2032 std::vector<CameraModel> models;
2034 if(cachedSignatures.contains(iter->first))
2036 const SensorData & data = cachedSignatures.find(iter->first)->sensorData();
2045 #ifdef RTABMAP_CPUTSDF 2046 if(
_ui->comboBox_meshingApproach->currentIndex()==2 &&
_ui->checkBox_assemble->isChecked())
2050 if(models.size()==1 && models[0].isValidForProjection() && models[0].imageHeight()>0 && models[0].imageWidth()>0)
2052 float tsdf_size =
_ui->doubleSpinBox_cputsdf_size->value();
2053 float cell_size =
_ui->doubleSpinBox_cputsdf_resolution->value();
2054 int num_random_splits =
_ui->spinBox_cputsdf_randomSplit->value();
2056 int desired_res = tsdf_size / cell_size;
2059 while (desired_res > n)
2065 tsdf.reset (
new cpu_tsdf::TSDFVolumeOctree);
2066 tsdf->setGridSize (tsdf_size, tsdf_size, tsdf_size);
2067 tsdf->setResolution (tsdf_res, tsdf_res, tsdf_res);
2068 float decimation = float(models[0].imageWidth()) / float(iter->second->width);
2069 tsdf->setImageSize (models[0].imageWidth()/decimation, models[0].imageHeight()/decimation);
2070 tsdf->setCameraIntrinsics (models[0].fx()/decimation, models[0].fy()/decimation, models[0].cx()/decimation, models[0].cy()/decimation);
2071 tsdf->setNumRandomSplts (num_random_splits);
2072 tsdf->setSensorDistanceBounds (0, 9999);
2073 tsdf->setIntegrateColor(
true);
2074 tsdf->setDepthTruncationLimits (
_ui->doubleSpinBox_cputsdf_tuncPos->value(),
_ui->doubleSpinBox_cputsdf_tuncNeg->value());
2087 if(tsdf.get() && models.size() == 1 && !models[0].localTransform().isNull())
2089 Eigen::Affine3d pose_rel_to_first_frame = ((poses.begin()->second.inverse() * poses.at(iter->first))*models[0].localTransform()).toEigen3d();
2090 if(!tsdf->integrateCloud(*
util3d::transformPointCloud(iter->second, models[0].localTransform().inverse()), pcl::PointCloud<pcl::Normal>(), pose_rel_to_first_frame))
2092 _progressDialog->
appendText(tr(
"CPU-TSDF: Failed integrating cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2096 _progressDialog->
appendText(tr(
"CPU-TSDF: Integrated cloud %1 (%2/%3) to TSDF volume").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2104 if((
_ui->comboBox_frame->isEnabled() &&
_ui->comboBox_frame->currentIndex() != 2) ||
2105 !iter->second->isOrganized())
2107 if(models.size() && !models[0].localTransform().isNull())
2109 viewpoint[0] = models[0].localTransform().x();
2110 viewpoint[1] = models[0].localTransform().y();
2111 viewpoint[2] = models[0].localTransform().z();
2123 _ui->doubleSpinBox_mesh_angleTolerance->value()*
M_PI/180.0,
2124 _ui->checkBox_mesh_quad->isEnabled() &&
_ui->checkBox_mesh_quad->isChecked(),
2125 _ui->spinBox_mesh_triangleSize->value(),
2128 if(
_ui->spinBox_mesh_minClusterSize->value() != 0)
2131 QApplication::processEvents();
2134 std::vector<std::set<int> > neighbors;
2135 std::vector<std::set<int> > vertexToPolygons;
2137 (
int)iter->second->size(),
2142 _ui->spinBox_mesh_minClusterSize->value()<0?0:
_ui->spinBox_mesh_minClusterSize->value());
2144 std::vector<pcl::Vertices> filteredPolygons(polygons.size());
2145 if(
_ui->spinBox_mesh_minClusterSize->value() < 0)
2148 std::list<std::list<int> >::iterator biggestClusterIndex = clusters.end();
2149 unsigned int biggestClusterSize = 0;
2150 for(std::list<std::list<int> >::iterator iter=clusters.begin(); iter!=clusters.end(); ++iter)
2152 if(iter->size() > biggestClusterSize)
2154 biggestClusterIndex = iter;
2155 biggestClusterSize = iter->size();
2158 if(biggestClusterIndex != clusters.end())
2161 for(std::list<int>::iterator jter=biggestClusterIndex->begin(); jter!=biggestClusterIndex->end(); ++jter)
2163 filteredPolygons[oi++] = polygons.at(*jter);
2165 filteredPolygons.resize(oi);
2171 for(std::list<std::list<int> >::iterator iter=clusters.begin(); iter!=clusters.end(); ++iter)
2173 for(std::list<int>::iterator jter=iter->begin(); jter!=iter->end(); ++jter)
2175 filteredPolygons[oi++] = polygons.at(*jter);
2178 filteredPolygons.resize(oi);
2180 int before = (int)polygons.size();
2181 polygons = filteredPolygons;
2183 if(polygons.size() == 0)
2185 std::string msg =
uFormat(
"All %d polygons filtered after polygon cluster filtering. Cluster minimum size is %d.", before,
_ui->spinBox_mesh_minClusterSize->value());
2191 QApplication::processEvents();
2194 _progressDialog->
appendText(tr(
"Mesh %1 created with %2 polygons (%3/%4).").arg(iter->first).arg(polygons.size()).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2196 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr denseCloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2197 std::vector<pcl::Vertices> densePolygons;
2200 if(!
_ui->checkBox_assemble->isChecked() ||
2201 (
_ui->checkBox_textureMapping->isEnabled() &&
2202 _ui->checkBox_textureMapping->isChecked() &&
2203 _ui->doubleSpinBox_voxelSize_assembled->value() == 0.0))
2205 if(
_ui->checkBox_assemble->isChecked())
2210 pcl::PolygonMesh::Ptr mesh(
new pcl::PolygonMesh);
2211 pcl::toPCLPointCloud2(*denseCloud, mesh->cloud);
2212 mesh->polygons = densePolygons;
2214 organizedIndices.insert(std::make_pair(iter->first, denseToOrganizedIndices));
2215 organizedCloudSizes.insert(std::make_pair(iter->first, cv::Size(iter->second->width, iter->second->height)));
2217 meshes.insert(std::make_pair(iter->first, mesh));
2222 if(mergedClouds->size() == 0)
2224 *mergedClouds = *denseCloud;
2225 mergedPolygons = densePolygons;
2236 _progressDialog->
appendText(tr(
"Mesh %1 not created (no valid points) (%2/%3).").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2242 if(cachedSignatures.contains(iter->first))
2244 const Signature & s = cachedSignatures.find(iter->first).value();
2253 _progressDialog->
appendText(tr(
"Mesh %1 not created (cloud is not organized). You may want to check cloud regeneration option (%2/%3).").arg(iter->first).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2258 QApplication::processEvents();
2265 if(
_ui->checkBox_assemble->isChecked() && mergedClouds->size())
2267 if(
_ui->doubleSpinBox_voxelSize_assembled->value())
2269 _progressDialog->
appendText(tr(
"Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").arg(mergedClouds->size()).arg(mergedPolygons.size()));
2270 QApplication::processEvents();
2275 _ui->doubleSpinBox_voxelSize_assembled->value(),
2280 unsigned int count = mergedPolygons.size();
2283 QApplication::processEvents();
2286 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2287 std::vector<pcl::Vertices> filteredPolygons;
2289 mergedClouds = filteredCloud;
2290 mergedPolygons = filteredPolygons;
2293 pcl::PolygonMesh::Ptr mesh(
new pcl::PolygonMesh);
2294 pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
2295 mesh->polygons = mergedPolygons;
2297 meshes.insert(std::make_pair(0, mesh));
2300 QApplication::processEvents();
2305 if(
_ui->comboBox_meshingApproach->currentIndex() == 0)
2313 QApplication::processEvents();
2315 QApplication::processEvents();
2318 for(std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr>::iterator iter=cloudsWithNormals.begin();
2319 iter!= cloudsWithNormals.end();
2320 ++iter,++cloudsAdded)
2322 pcl::PolygonMesh::Ptr mesh(
new pcl::PolygonMesh);
2323 if(
_ui->comboBox_meshingApproach->currentIndex() == 0)
2327 _ui->doubleSpinBox_gp3Radius->value(),
2328 _ui->doubleSpinBox_gp3Mu->value());
2332 pcl::Poisson<pcl::PointXYZRGBNormal> poisson;
2333 poisson.setOutputPolygons(
_ui->checkBox_poisson_outputPolygons->isEnabled()?
_ui->checkBox_poisson_outputPolygons->isChecked():
false);
2334 poisson.setManifold(
_ui->checkBox_poisson_manifold->isChecked());
2335 poisson.setSamplesPerNode(
_ui->doubleSpinBox_poisson_samples->value());
2336 int depth =
_ui->spinBox_poisson_depth->value();
2341 float mapLength =
uMax3(max[0]-min[0], max[1]-min[1], max[2]-min[2]);
2343 for(
int i=6; i<12; ++i)
2345 if(mapLength/
float(1<<i) < 0.03
f)
2353 .arg(
int(max[0]-min[0]))
2354 .arg(
int(max[1]-min[1]))
2355 .arg(
int(max[2]-min[2])));
2356 QApplication::processEvents();
2358 QApplication::processEvents();
2360 poisson.setDepth(depth);
2361 poisson.setIsoDivide(
_ui->spinBox_poisson_iso->value());
2362 poisson.setSolverDivide(
_ui->spinBox_poisson_solver->value());
2363 poisson.setMinDepth(
_ui->spinBox_poisson_minDepth->value());
2364 poisson.setPointWeight(
_ui->doubleSpinBox_poisson_pointWeight->value());
2365 poisson.setScale(
_ui->doubleSpinBox_poisson_scale->value());
2366 poisson.setInputCloud(iter->second);
2367 poisson.reconstruct(*mesh);
2370 _progressDialog->
appendText(tr(
"Mesh %1 created with %2 polygons (%3/%4).").arg(iter->first).arg(mesh->polygons.size()).arg(cloudsAdded).arg(cloudsWithNormals.size()));
2371 QApplication::processEvents();
2373 if(mesh->polygons.size()>0)
2377 if(!
_ui->checkBox_fromDepth->isChecked())
2380 int maxIntensity = 1;
2382 for(
size_t i=0; i<iter->second->size(); ++i)
2385 int(iter->second->points[i].r) |
2386 int(iter->second->points[i].g) << 8 |
2387 int(iter->second->points[i].b) << 16 |
2388 int(iter->second->points[i].a) << 24;
2389 if(intensity > maxIntensity)
2391 maxIntensity = intensity;
2395 for(
size_t i=0; i<iter->second->size(); ++i)
2398 int(iter->second->points[i].r) |
2399 int(iter->second->points[i].g) << 8 |
2400 int(iter->second->points[i].b) << 16 |
2401 int(iter->second->points[i].a) << 24;
2402 intensity = intensity*255/maxIntensity;
2403 iter->second->points[i].r = (
unsigned char)intensity;
2404 iter->second->points[i].g = (
unsigned char)intensity;
2405 iter->second->points[i].b = (
unsigned char)intensity;
2406 iter->second->points[i].a = (
unsigned char)255;
2410 util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
2412 _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)
_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
2413 _ui->spinBox_meshMaxPolygons->isEnabled()?
_ui->spinBox_meshMaxPolygons->value():0,
2415 (float)
_ui->doubleSpinBox_transferColorRadius->value(),
2416 !(
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked()),
2417 _ui->checkBox_cleanMesh->isChecked(),
2418 _ui->spinBox_mesh_minClusterSize->value(),
2420 meshes.insert(std::make_pair(iter->first, mesh));
2429 QApplication::processEvents();
2437 else if(
_ui->checkBox_meshing->isChecked())
2439 std::string msg =
uFormat(
"Some clouds are 2D laser scans. Meshing can be done only from RGB-D clouds or 3D laser scans.");
2445 #ifdef RTABMAP_CPUTSDF 2449 QApplication::processEvents();
2451 QApplication::processEvents();
2453 cpu_tsdf::MarchingCubesTSDFOctree mc;
2454 mc.setMinWeight (
_ui->doubleSpinBox_cputsdf_minWeight->value());
2455 mc.setInputTSDF (tsdf);
2456 mc.setColorByRGB (
true);
2457 pcl::PolygonMesh::Ptr mesh (
new pcl::PolygonMesh);
2458 mc.reconstruct (*mesh);
2459 _progressDialog->
appendText(tr(
"CPU-TSDF: Creating mesh from TSDF volume...done! %1 polygons").arg(mesh->polygons.size()));
2462 if(mesh->polygons.size()>0)
2465 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr
vertices (
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2466 pcl::fromPCLPointCloud2 (mesh->cloud, *vertices);
2468 if(
_ui->doubleSpinBox_cputsdf_flattenRadius->value()>0.0)
2471 QApplication::processEvents();
2473 QApplication::processEvents();
2475 float min_dist =
_ui->doubleSpinBox_cputsdf_flattenRadius->value();
2476 pcl::search::KdTree<pcl::PointXYZRGBNormal> vert_tree (
true);
2477 vert_tree.setInputCloud (vertices);
2479 std::vector<int> vertex_remap (vertices->size (), -1);
2481 std::vector<int> neighbors;
2482 std::vector<float> dists;
2483 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr vertices_new(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2484 vertices_new->resize(vertices->size ());
2485 for (
size_t i = 0; i < vertices->size (); i++)
2487 if (vertex_remap[i] >= 0)
2489 vertex_remap[i] = idx;
2490 vert_tree.radiusSearch (i, min_dist, neighbors, dists);
2491 for (
size_t j = 1; j < neighbors.size (); j++)
2493 if (dists[j] < min_dist)
2494 vertex_remap[neighbors[j]] = idx;
2496 vertices_new->at(idx++) = vertices->at (i);
2498 vertices_new->resize(idx);
2499 std::vector<size_t> faces_to_remove;
2500 size_t face_idx = 0;
2501 for (
size_t i = 0; i < mesh->polygons.size (); i++)
2503 pcl::Vertices &v = mesh->polygons[i];
2504 for (
size_t j = 0; j < v.vertices.size (); j++)
2506 v.vertices[j] = vertex_remap[v.vertices[j]];
2508 if (!(v.vertices[0] == v.vertices[1] || v.vertices[1] == v.vertices[2] || v.vertices[2] == v.vertices[0]))
2510 mesh->polygons[face_idx++] = mesh->polygons[i];
2513 mesh->polygons.resize (face_idx);
2514 pcl::toPCLPointCloud2 (*vertices_new, mesh->cloud);
2515 vertices = vertices_new;
2518 pcl::fromPCLPointCloud2(mesh->cloud, *vertices);
2520 util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
2522 _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)
_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
2523 _ui->spinBox_meshMaxPolygons->isEnabled()?
_ui->spinBox_meshMaxPolygons->value():0,
2525 (float)
_ui->doubleSpinBox_transferColorRadius->value(),
2526 !(
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked()),
2527 _ui->checkBox_cleanMesh->isChecked(),
2528 _ui->spinBox_mesh_minClusterSize->value(),
2530 meshes.insert(std::make_pair(0, mesh));
2539 #ifdef RTABMAP_OPENCHISEL 2543 QApplication::processEvents();
2545 QApplication::processEvents();
2547 const chisel::MeshMap& meshMap = chiselMap->GetChunkManager().GetAllMeshes();
2555 _progressDialog->
appendText(tr(
"OpenChisel: Creating mesh from TSDF volume...done! %1 polygons").arg(mesh->polygons.size()));
2558 if(mesh->polygons.size()>0)
2560 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2561 pcl::fromPCLPointCloud2(mesh->cloud, *mergedClouds);
2562 if(
_ui->checkBox_openchisel_mergeVertices->isChecked())
2564 _progressDialog->
appendText(tr(
"Filtering assembled mesh for close vertices (points=%1, polygons=%2)...").arg(mergedClouds->size()).arg(mesh->polygons.size()));
2565 QApplication::processEvents();
2570 _ui->doubleSpinBox_voxelSize_assembled->value()/2.0,
2575 unsigned int count = mesh->polygons.size();
2578 QApplication::processEvents();
2581 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr filteredCloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
2582 std::vector<pcl::Vertices> filteredPolygons;
2583 count = mergedClouds->size();
2585 mergedClouds = filteredCloud;
2586 pcl::toPCLPointCloud2(*mergedClouds, mesh->cloud);
2587 mesh->polygons = filteredPolygons;
2589 QApplication::processEvents();
2592 util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
2594 _ui->doubleSpinBox_meshDecimationFactor->isEnabled()?(float)
_ui->doubleSpinBox_meshDecimationFactor->value():0.0f,
2595 _ui->spinBox_meshMaxPolygons->isEnabled()?
_ui->spinBox_meshMaxPolygons->value():0,
2597 (float)
_ui->doubleSpinBox_transferColorRadius->value(),
2598 !(
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked()),
2599 _ui->checkBox_cleanMesh->isChecked(),
2600 _ui->spinBox_mesh_minClusterSize->value(),
2602 meshes.insert(std::make_pair(0, mesh));
2619 UDEBUG(
"texture mapping=%d",
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked()?1:0);
2620 if(!has2dScans && !meshes.empty() &&
_ui->checkBox_textureMapping->isEnabled() &&
_ui->checkBox_textureMapping->isChecked())
2623 QApplication::processEvents();
2625 QApplication::processEvents();
2628 for(std::map<int, pcl::PolygonMesh::Ptr>::iterator iter=meshes.begin();
2629 iter!= meshes.end();
2632 std::map<int, Transform> cameras;
2633 if(iter->first == 0)
2640 cameras.insert(std::make_pair(iter->first,
_ui->checkBox_assemble->isChecked()?poses.at(iter->first):
Transform::getIdentity()));
2642 std::map<int, Transform> cameraPoses;
2643 std::map<int, std::vector<CameraModel> > cameraModels;
2644 std::map<int, cv::Mat > cameraDepths;
2645 int ignoredCameras = 0;
2646 for(std::map<int, Transform>::iterator jter=cameras.begin(); jter!=cameras.end(); ++jter)
2648 if(validCameras.find(jter->first) != validCameras.end())
2650 std::vector<CameraModel> models;
2652 bool cacheHasCompressedImage =
false;
2653 if(cachedSignatures.contains(jter->first))
2655 const SensorData & data = cachedSignatures.find(jter->first)->sensorData();
2670 models.push_back(stereoModel.
left());
2672 else if(models.size() == 0 || !models[0].isValidForProjection())
2677 if(!jter->second.isNull() && models.size())
2680 bool blurryImage =
false;
2681 bool getDepth = !stereo &&
_ui->doubleSpinBox_meshingTextureMaxDepthError->value() >= 0.0f;
2683 std::vector<float> velocity;
2684 if(models[0].imageWidth() == 0 || models[0].imageHeight() == 0)
2688 if(cacheHasCompressedImage)
2690 cachedSignatures.find(jter->first)->sensorData().uncompressDataConst(&img, getDepth?&depth:0);
2691 velocity = cachedSignatures.find(jter->first)->getVelocity();
2699 if(
_ui->checkBox_cameraFilter->isChecked() &&
2700 (
_ui->doubleSpinBox_cameraFilterVel->value()>0.0 ||
_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
2711 cv::Size imageSize = img.size();
2712 imageSize.width /= models.size();
2713 for(
unsigned int i=0; i<models.size(); ++i)
2715 models[i].setImageSize(imageSize);
2720 bool getImg =
_ui->checkBox_cameraFilter->isChecked() &&
_ui->doubleSpinBox_laplacianVariance->value()>0.0;
2722 if(cacheHasCompressedImage)
2724 cachedSignatures.find(jter->first)->sensorData().uncompressDataConst(getImg?&img:0, getDepth?&depth:0);
2725 velocity = cachedSignatures.find(jter->first)->getVelocity();
2733 if(
_ui->checkBox_cameraFilter->isChecked() &&
2734 (
_ui->doubleSpinBox_cameraFilterVel->value()>0.0 ||
_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
2746 if(
_ui->checkBox_cameraFilter->isChecked())
2750 (
_ui->doubleSpinBox_cameraFilterVel->value()>0.0 ||
_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0))
2752 if(velocity.size() == 6)
2754 float transVel =
uMax3(fabs(velocity[0]), fabs(velocity[1]), fabs(velocity[2]));
2755 float rotVel =
uMax3(fabs(velocity[3]), fabs(velocity[4]), fabs(velocity[5]));
2756 if(
_ui->doubleSpinBox_cameraFilterVel->value()>0.0 && transVel >
_ui->doubleSpinBox_cameraFilterVel->value())
2758 msg =
uFormat(
"Fast motion detected for camera %d (speed=%f m/s > thr=%f m/s), camera is ignored for texturing.", jter->first, transVel,
_ui->doubleSpinBox_cameraFilterVel->value());
2761 else if(
_ui->doubleSpinBox_cameraFilterVelRad->value()>0.0 && rotVel >
_ui->doubleSpinBox_cameraFilterVelRad->value())
2763 msg =
uFormat(
"Fast motion detected for camera %d (speed=%f rad/s > thr=%f rad/s), camera is ignored for texturing.", jter->first, rotVel,
_ui->doubleSpinBox_cameraFilterVelRad->value());
2769 UWARN(
"Camera motion filtering is set, but velocity of camera %d is not available.", jter->first);
2773 if(!blurryImage && !img.empty() &&
_ui->doubleSpinBox_laplacianVariance->value()>0.0)
2775 cv::Mat imgLaplacian;
2776 cv::Laplacian(img, imgLaplacian, CV_16S);
2778 cv::meanStdDev(imgLaplacian, m, s);
2779 double stddev_pxl = s.at<
double>(0);
2780 double var = stddev_pxl*stddev_pxl;
2781 if(var < _ui->doubleSpinBox_laplacianVariance->value())
2784 msg =
uFormat(
"Camera's image %d is detected as blurry (var=%f < thr=%f), camera is ignored for texturing.", jter->first, var,
_ui->doubleSpinBox_laplacianVariance->value());
2790 QApplication::processEvents();
2795 if(!blurryImage && models[0].imageWidth() != 0 && models[0].imageHeight() != 0)
2797 cameraPoses.insert(std::make_pair(jter->first, jter->second));
2798 cameraModels.insert(std::make_pair(jter->first, models));
2801 cameraDepths.insert(std::make_pair(jter->first, depth));
2807 if(ignoredCameras > (
int)validCameras.size()/2)
2809 std::string msg =
uFormat(
"More than 50%% of the cameras (%d/%d) have been filtered for " 2810 "too fast motion and/or blur level. You may adjust the corresponding thresholds.",
2811 ignoredCameras, (
int)validCameras.size());
2815 QApplication::processEvents();
2818 if(cameraPoses.size() && iter->second->polygons.size())
2820 pcl::TextureMesh::Ptr textureMesh(
new pcl::TextureMesh);
2821 std::map<int, std::vector<int> >::iterator oter = organizedIndices.find(iter->first);
2822 std::map<int, cv::Size>::iterator ster = organizedCloudSizes.find(iter->first);
2823 if(iter->first != 0 && oter != organizedIndices.end())
2825 UASSERT(ster!=organizedCloudSizes.end()&&ster->first == oter->first);
2826 UDEBUG(
"Texture by pixels");
2827 textureMesh->cloud = iter->second->cloud;
2828 textureMesh->tex_polygons.push_back(iter->second->polygons);
2829 int w = ster->second.width;
2830 int h = ster->second.height;
2832 if(textureMesh->tex_polygons.size() && textureMesh->tex_polygons[0].size())
2834 textureMesh->tex_coordinates.resize(1);
2837 int polygonSize = (int)textureMesh->tex_polygons[0][0].vertices.size();
2838 textureMesh->tex_coordinates[0].resize(polygonSize*textureMesh->tex_polygons[0].size());
2839 for(
unsigned int i=0; i<textureMesh->tex_polygons[0].size(); ++i)
2841 const pcl::Vertices &
vertices = textureMesh->tex_polygons[0][i];
2842 UASSERT(polygonSize == (
int)vertices.vertices.size());
2843 for(
int k=0; k<polygonSize; ++k)
2846 UASSERT(vertices.vertices[k] < oter->second.size());
2847 int originalVertex = oter->second[vertices.vertices[k]];
2848 textureMesh->tex_coordinates[0][i*polygonSize+k] = Eigen::Vector2f(
2849 float(originalVertex % w) /
float(w),
2850 float(h - originalVertex / w) /
float(h));
2854 pcl::TexMaterial mesh_material;
2855 mesh_material.tex_d = 1.0f;
2856 mesh_material.tex_Ns = 75.0f;
2857 mesh_material.tex_illum = 1;
2859 std::stringstream tex_name;
2860 tex_name <<
"material_" << iter->first;
2861 tex_name >> mesh_material.tex_name;
2863 mesh_material.tex_file =
uFormat(
"%d", iter->first);
2864 textureMesh->tex_materials.push_back(mesh_material);
2868 UWARN(
"No polygons for mesh %d!?", iter->first);
2873 UDEBUG(
"Texture by projection");
2875 if(cameraPoses.size() &&
_ui->checkBox_cameraFilter->isChecked())
2877 int before = (int)cameraPoses.size();
2879 _ui->doubleSpinBox_cameraFilterRadius->value(),
2880 _ui->doubleSpinBox_cameraFilterAngle->value());
2881 for(std::map<
int, std::vector<CameraModel> >::iterator modelIter = cameraModels.begin(); modelIter!=cameraModels.end();)
2883 if(cameraPoses.find(modelIter->first)==cameraPoses.end())
2885 cameraModels.erase(modelIter++);
2886 cameraDepths.erase(modelIter->first);
2893 _progressDialog->
appendText(tr(
"Camera filtering: keeping %1/%2 cameras for texturing.").arg(cameraPoses.size()).arg(before));
2894 QApplication::processEvents();
2896 QApplication::processEvents();
2906 if(cameraModels.size() && cameraModels.begin()->second.size()>1)
2911 std::vector<float> roiRatios;
2912 QStringList strings =
_ui->lineEdit_meshingTextureRoiRatios->text().split(
' ');
2913 if(!
_ui->lineEdit_meshingTextureRoiRatios->text().isEmpty())
2915 if(strings.size()==4)
2917 roiRatios.resize(4);
2918 roiRatios[0]=strings[0].toDouble();
2919 roiRatios[1]=strings[1].toDouble();
2920 roiRatios[2]=strings[2].toDouble();
2921 roiRatios[3]=strings[3].toDouble();
2922 if(!(roiRatios[0]>=0.0
f && roiRatios[0]<=1.0
f &&
2923 roiRatios[1]>=0.0
f && roiRatios[1]<=1.0
f &&
2924 roiRatios[2]>=0.0
f && roiRatios[2]<=1.0
f &&
2925 roiRatios[3]>=0.0
f && roiRatios[3]<=1.0
f))
2930 if(roiRatios.empty())
2932 QString msg = tr(
"Wrong ROI format. Region of Interest (ROI) must have 4 values [left right top bottom] between 0 and 1 separated by space (%1), ignoring it for texturing...").arg(
_ui->lineEdit_meshingTextureRoiRatios->text());
2933 UWARN(msg.toStdString().c_str());
2944 _ui->doubleSpinBox_meshingTextureMaxDistance->value(),
2945 _ui->doubleSpinBox_meshingTextureMaxDepthError->value(),
2946 _ui->doubleSpinBox_meshingTextureMaxAngle->value()*
M_PI/180.0,
2947 _ui->spinBox_mesh_minTextureClusterSize->value(),
2950 cameraPoses.size()>1?&textureVertexToPixels:0,
2951 _ui->checkBox_distanceToCamPolicy->isChecked());
2959 if(
_ui->checkBox_cleanMesh->isChecked())
2961 unsigned int totalSize = 0;
2962 for(
unsigned int t=0; t<textureMesh->tex_polygons.size(); ++t)
2964 totalSize+=textureMesh->tex_polygons[t].size();
2969 unsigned int totalSizeAfter = 0;
2970 for(
unsigned int t=0; t<textureMesh->tex_polygons.size(); ++t)
2972 totalSizeAfter+=textureMesh->tex_polygons[t].size();
2978 textureMeshes.insert(std::make_pair(iter->first, textureMesh));
2980 else if(cameraPoses.size() == 0)
2982 _progressDialog->
appendText(tr(
"No cameras from %1 poses with valid calibration found!").arg(poses.size()), Qt::darkYellow);
2984 UWARN(
"No camera poses!?");
2990 UWARN(
"No polygons!");
2993 _progressDialog->
appendText(tr(
"TextureMesh %1 created [cameras=%2] (%3/%4).").arg(iter->first).arg(cameraPoses.size()).arg(++i).arg(meshes.size()));
2995 QApplication::processEvents();
3002 if(textureMeshes.size() > 1 &&
_ui->checkBox_assemble->isChecked())
3004 UDEBUG(
"Concatenate texture meshes");
3006 QApplication::processEvents();
3008 QApplication::processEvents();
3011 textureMeshes.clear();
3012 textureMeshes.insert(std::make_pair(0, assembledMesh));
3023 const std::map<int, Transform> & poses,
3024 const QMap<int, Signature> & cachedSignatures,
3025 const std::map<
int, std::pair<pcl::PointCloud<pcl::PointXYZRGB>::Ptr, pcl::IndicesPtr> > & cachedClouds,
3026 const std::map<int, LaserScan> & cachedScans,
3028 bool & has2dScans)
const 3031 std::map<int, std::pair<pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr, pcl::IndicesPtr> > clouds;
3033 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr previousCloud;
3034 pcl::IndicesPtr previousIndices;
3036 for(std::map<int, Transform>::const_iterator iter = poses.lower_bound(1); iter!=poses.end() && !
_canceled; ++iter, ++index)
3039 int totalIndices = 0;
3040 if(!iter->second.isNull())
3042 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
3043 pcl::IndicesPtr indices(
new std::vector<int>);
3045 if(
_ui->checkBox_regenerate->isChecked())
3049 if(cachedSignatures.contains(iter->first))
3051 const Signature & s = cachedSignatures.find(iter->first).value();
3053 cv::Mat image,depth;
3055 _ui->checkBox_fromDepth->isChecked()?&image:0,
3056 _ui->checkBox_fromDepth->isChecked()?&depth:0,
3057 !
_ui->checkBox_fromDepth->isChecked()?&scan:0);
3061 cv::Mat image,depth;
3062 _dbDriver->
getNodeData(iter->first, data,
_ui->checkBox_fromDepth->isChecked(), !
_ui->checkBox_fromDepth->isChecked(),
false,
false);
3064 _ui->checkBox_fromDepth->isChecked()?&image:0,
3065 _ui->checkBox_fromDepth->isChecked()?&depth:0,
3066 !
_ui->checkBox_fromDepth->isChecked()?&scan:0);
3072 if(!depth.empty() &&
_ui->spinBox_fillDepthHoles->value() > 0)
3077 if(!depth.empty() &&
3078 !
_ui->lineEdit_distortionModel->text().isEmpty() &&
3079 QFileInfo(
_ui->lineEdit_distortionModel->text()).exists())
3082 model.
load(
_ui->lineEdit_distortionModel->text().toStdString());
3083 depth = depth.clone();
3088 if(!depth.empty() &&
_ui->checkBox_bilateral->isChecked())
3091 _ui->doubleSpinBox_bilateral_sigmaS->value(),
3092 _ui->doubleSpinBox_bilateral_sigmaR->value());
3101 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
3102 std::vector<float> roiRatios;
3103 if(!
_ui->lineEdit_roiRatios->text().isEmpty())
3105 QStringList values =
_ui->lineEdit_roiRatios->text().split(
' ');
3106 if(values.size() == 4)
3108 roiRatios.resize(4);
3109 for(
int i=0; i<values.size(); ++i)
3111 roiRatios[i] =
uStr2Float(values[i].toStdString().c_str());
3117 _ui->spinBox_decimation->value() == 0?1:
_ui->spinBox_decimation->value(),
3118 _ui->doubleSpinBox_maxDepth->value(),
3119 _ui->doubleSpinBox_minDepth->value(),
3124 if(cloudWithoutNormals->size())
3127 if(!(
_ui->comboBox_pipeline->currentIndex()==0 &&
_ui->checkBox_meshing->isChecked()) &&
_ui->doubleSpinBox_voxelSize_assembled->value()>0.0)
3129 cloudWithoutNormals =
util3d::voxelize(cloudWithoutNormals, indices,
_ui->doubleSpinBox_voxelSize_assembled->value());
3130 indices->resize(cloudWithoutNormals->size());
3131 for(
unsigned int i=0; i<indices->size(); ++i)
3138 Eigen::Vector3f viewPoint(0.0
f,0.0
f,0.0
f);
3141 localTransform = data.
cameraModels()[0].localTransform();
3142 viewPoint[0] = data.
cameraModels()[0].localTransform().x();
3143 viewPoint[1] = data.
cameraModels()[0].localTransform().y();
3144 viewPoint[2] = data.
cameraModels()[0].localTransform().z();
3154 if(
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
3156 pcl::PointCloud<pcl::Normal>::Ptr normals =
util3d::computeNormals(cloudWithoutNormals, indices,
_ui->spinBox_normalKSearch->value(),
_ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
3157 pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
3161 pcl::copyPointCloud(*cloudWithoutNormals, *cloud);
3164 if(
_ui->checkBox_subtraction->isChecked() &&
3165 _ui->doubleSpinBox_subtractPointFilteringRadius->value() > 0.0)
3167 pcl::IndicesPtr beforeSubtractionIndices = indices;
3168 if( cloud->size() &&
3169 previousCloud.get() != 0 &&
3170 previousIndices.get() != 0 &&
3171 previousIndices->size() &&
3181 _ui->doubleSpinBox_subtractPointFilteringRadius->value(),
3182 _ui->doubleSpinBox_subtractPointFilteringAngle->value(),
3183 _ui->spinBox_subtractFilteringMinPts->value());
3185 previousCloud = cloud;
3186 previousIndices = beforeSubtractionIndices;
3187 previousPose = iter->second;
3191 else if(!
_ui->checkBox_fromDepth->isChecked() && !scan.
isEmpty())
3194 _ui->spinBox_decimation_scan->value(),
3195 _ui->doubleSpinBox_rangeMin->value(),
3196 _ui->doubleSpinBox_rangeMax->value(),
3197 _ui->doubleSpinBox_voxelSize_assembled->value(),
3198 _ui->spinBox_normalKSearch->value(),
3199 _ui->doubleSpinBox_normalRadiusSearch->value());
3203 indices->resize(cloud->size());
3204 for(
unsigned int i=0; i<indices->size(); ++i)
3212 if(cachedSignatures.contains(iter->first))
3214 const Signature & s = cachedSignatures.find(iter->first).value();
3223 UERROR(
"Cloud %d not found in cache!", iter->first);
3226 if(!cloud->empty() &&
3227 (
_ui->doubleSpinBox_ceilingHeight->value() != 0.0 ||
_ui->doubleSpinBox_floorHeight->value() != 0.0))
3229 float min =
_ui->doubleSpinBox_floorHeight->value();
3230 float max =
_ui->doubleSpinBox_ceilingHeight->value();
3235 min!=0.0f&&min<max?min:std::numeric_limits<float>::lowest(),
3239 else if(
_ui->checkBox_fromDepth->isChecked() &&
uContains(cachedClouds, iter->first))
3241 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudWithoutNormals;
3242 if(!
_ui->checkBox_meshing->isChecked() &&
3243 _ui->doubleSpinBox_voxelSize_assembled->value() > 0.0)
3246 cachedClouds.at(iter->first).first,
3247 cachedClouds.at(iter->first).second,
3248 _ui->doubleSpinBox_voxelSize_assembled->value());
3251 indices->resize(cloudWithoutNormals->size());
3252 for(
unsigned int i=0; i<cloudWithoutNormals->size(); ++i)
3259 cloudWithoutNormals = cachedClouds.at(iter->first).first;
3260 indices = cachedClouds.at(iter->first).second;
3264 Eigen::Vector3f viewPoint(0.0
f,0.0
f,0.0
f);
3265 std::vector<CameraModel> models;
3267 if(cachedSignatures.contains(iter->first))
3269 const Signature & s = cachedSignatures.find(iter->first).value();
3278 if(models.size() && !models[0].localTransform().isNull())
3280 localTransform = models[0].localTransform();
3281 viewPoint[0] = models[0].localTransform().
x();
3282 viewPoint[1] = models[0].localTransform().y();
3283 viewPoint[2] = models[0].localTransform().z();
3294 _progressDialog->
appendText(tr(
"Cached cloud %1 is not found in cached data, the view point for normal computation will not be set (%2/%3).").arg(iter->first).arg(index).arg(poses.size()), Qt::darkYellow);
3297 if(
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
3299 pcl::PointCloud<pcl::Normal>::Ptr normals =
util3d::computeNormals(cloudWithoutNormals, indices,
_ui->spinBox_normalKSearch->value(),
_ui->doubleSpinBox_normalRadiusSearch->value(), viewPoint);
3300 pcl::concatenateFields(*cloudWithoutNormals, *normals, *cloud);
3304 pcl::copyPointCloud(*cloudWithoutNormals, *cloud);
3307 else if(!
_ui->checkBox_fromDepth->isChecked() &&
uContains(cachedScans, iter->first))
3310 _ui->spinBox_decimation_scan->value(),
3311 _ui->doubleSpinBox_rangeMin->value(),
3312 _ui->doubleSpinBox_rangeMax->value(),
3313 _ui->doubleSpinBox_voxelSize_assembled->value(),
3314 _ui->spinBox_normalKSearch->value(),
3315 _ui->doubleSpinBox_normalRadiusSearch->value());
3319 indices->resize(cloud->size());
3320 for(
unsigned int i=0; i<indices->size(); ++i)
3328 if(cachedSignatures.contains(iter->first))
3330 const Signature & s = cachedSignatures.find(iter->first).value();
3339 _progressDialog->
appendText(tr(
"Cached cloud %1 not found. You may want to regenerate the clouds (%2/%3).").arg(iter->first).arg(index).arg(poses.size()), Qt::darkYellow);
3345 if(
_ui->checkBox_filtering->isChecked() &&
3346 _ui->doubleSpinBox_filteringRadius->value() > 0.0f &&
3347 _ui->spinBox_filteringMinNeighbors->value() > 0)
3349 indices =
util3d::radiusFiltering(cloud, indices,
_ui->doubleSpinBox_filteringRadius->value(),
_ui->spinBox_filteringMinNeighbors->value());
3352 if((
_ui->comboBox_frame->isEnabled() &&
_ui->comboBox_frame->currentIndex()==2) && cloud->isOrganized())
3356 else if(
_ui->comboBox_frame->isEnabled() &&
_ui->comboBox_frame->currentIndex()==3)
3361 clouds.insert(std::make_pair(iter->first, std::make_pair(cloud, indices)));
3362 points = (int)cloud->size();
3363 totalIndices = (int)indices->size();
3368 UERROR(
"transform is null!?");
3373 if(
_ui->checkBox_regenerate->isChecked())
3376 .arg(iter->first).arg(points).arg(totalIndices).arg(index).arg(poses.size()));
3381 .arg(iter->first).arg(points).arg(totalIndices).arg(index).arg(poses.size()));
3389 QApplication::processEvents();
3397 const QString & workingDirectory,
3398 const std::map<int, Transform> & poses,
3399 const std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr> & clouds,
3402 if(clouds.size() == 1)
3404 QString path = QFileDialog::getSaveFileName(
this, tr(
"Save cloud to ..."), workingDirectory+QDir::separator()+
"cloud.ply", tr(
"Point cloud data (*.ply *.pcd)"));
3407 if(clouds.begin()->second->size())
3409 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudRGBWithoutNormals;
3410 pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIWithoutNormals;
3411 pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloudIWithNormals;
3412 if(!
_ui->checkBox_fromDepth->isChecked())
3415 if(
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
3417 cloudIWithNormals.reset(
new pcl::PointCloud<pcl::PointXYZINormal>);
3418 cloudIWithNormals->resize(clouds.begin()->second->size());
3419 for(
unsigned int i=0; i<cloudIWithNormals->size(); ++i)
3421 cloudIWithNormals->points[i].x = clouds.begin()->second->points[i].x;
3422 cloudIWithNormals->points[i].y = clouds.begin()->second->points[i].y;
3423 cloudIWithNormals->points[i].z = clouds.begin()->second->points[i].z;
3424 cloudIWithNormals->points[i].normal_x = clouds.begin()->second->points[i].normal_x;
3425 cloudIWithNormals->points[i].normal_y = clouds.begin()->second->points[i].normal_y;
3426 cloudIWithNormals->points[i].normal_z = clouds.begin()->second->points[i].normal_z;
3427 cloudIWithNormals->points[i].curvature = clouds.begin()->second->points[i].curvature;
3428 int * intensity = (
int *)&cloudIWithNormals->points[i].intensity;
3430 int(clouds.begin()->second->points[i].r) |
3431 int(clouds.begin()->second->points[i].g) << 8 |
3432 int(clouds.begin()->second->points[i].b) << 16 |
3433 int(clouds.begin()->second->points[i].a) << 24;
3438 cloudIWithoutNormals.reset(
new pcl::PointCloud<pcl::PointXYZI>);
3439 cloudIWithoutNormals->resize(clouds.begin()->second->size());
3440 for(
unsigned int i=0; i<cloudIWithoutNormals->size(); ++i)
3442 cloudIWithoutNormals->points[i].x = clouds.begin()->second->points[i].x;
3443 cloudIWithoutNormals->points[i].y = clouds.begin()->second->points[i].y;
3444 cloudIWithoutNormals->points[i].z = clouds.begin()->second->points[i].z;
3445 int * intensity = (
int *)&cloudIWithoutNormals->points[i].intensity;
3447 int(clouds.begin()->second->points[i].r) |
3448 int(clouds.begin()->second->points[i].g) << 8 |
3449 int(clouds.begin()->second->points[i].b) << 16 |
3450 int(clouds.begin()->second->points[i].a) << 24;
3454 else if(
_ui->spinBox_normalKSearch->value()<=0 &&
_ui->doubleSpinBox_normalRadiusSearch->value()<=0.0)
3456 cloudRGBWithoutNormals.reset(
new pcl::PointCloud<pcl::PointXYZRGB>);
3457 pcl::copyPointCloud(*clouds.begin()->second, *cloudRGBWithoutNormals);
3462 bool success =
false;
3463 if(QFileInfo(path).suffix() ==
"pcd")
3465 if(cloudIWithNormals.get())
3467 success = pcl::io::savePCDFile(path.toStdString(), *cloudIWithNormals, binaryMode) == 0;
3469 else if(cloudIWithoutNormals.get())
3471 success = pcl::io::savePCDFile(path.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
3473 else if(cloudRGBWithoutNormals.get())
3475 success = pcl::io::savePCDFile(path.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
3479 success = pcl::io::savePCDFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
3482 else if(QFileInfo(path).suffix() ==
"ply" || QFileInfo(path).suffix() ==
"")
3484 if(QFileInfo(path).suffix() ==
"")
3490 if(cloudIWithNormals.get())
3492 success = pcl::io::savePLYFile(path.toStdString(), *cloudIWithNormals, binaryMode) == 0;
3494 else if(cloudIWithoutNormals.get())
3496 success = pcl::io::savePLYFile(path.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
3498 else if(cloudRGBWithoutNormals.get())
3500 success = pcl::io::savePLYFile(path.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
3504 success = pcl::io::savePLYFile(path.toStdString(), *clouds.begin()->second, binaryMode) == 0;
3509 UERROR(
"Extension not recognized! (%s) Should be one of (*.ply *.pcd).", QFileInfo(path).suffix().toStdString().c_str());
3516 QMessageBox::information(
this, tr(
"Save successful!"), tr(
"Cloud saved to \"%1\"").arg(path));
3520 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Failed to save to \"%1\"").arg(path));
3525 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Cloud is empty..."));
3529 else if(clouds.size())
3531 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Save clouds to (*.ply *.pcd)..."), workingDirectory, 0);
3536 items.push_back(
"ply");
3537 items.push_back(
"pcd");
3538 QString suffix = QInputDialog::getItem(
this, tr(
"File format"), tr(
"Which format?"), items, 0,
false, &ok);
3542 QString prefix = QInputDialog::getText(
this, tr(
"File prefix"), tr(
"Prefix:"), QLineEdit::Normal,
"cloud", &ok);
3546 for(std::map<
int, pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr >::const_iterator iter=clouds.begin(); iter!=clouds.end(); ++iter)
3548 if(iter->second->size())
3550 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformedCloud;
3553 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudRGBWithoutNormals;
3554 pcl::PointCloud<pcl::PointXYZI>::Ptr cloudIWithoutNormals;
3555 pcl::PointCloud<pcl::PointXYZINormal>::Ptr cloudIWithNormals;
3556 if(!
_ui->checkBox_fromDepth->isChecked())
3559 if(
_ui->spinBox_normalKSearch->value()>0 ||
_ui->doubleSpinBox_normalRadiusSearch->value()>0.0)
3561 cloudIWithNormals.reset(
new pcl::PointCloud<pcl::PointXYZINormal>);
3562 cloudIWithNormals->resize(transformedCloud->size());
3563 for(
unsigned int i=0; i<cloudIWithNormals->size(); ++i)
3565 cloudIWithNormals->points[i].x = transformedCloud->points[i].x;
3566 cloudIWithNormals->points[i].y = transformedCloud->points[i].y;
3567 cloudIWithNormals->points[i].z = transformedCloud->points[i].z;
3568 cloudIWithNormals->points[i].normal_x = transformedCloud->points[i].normal_x;
3569 cloudIWithNormals->points[i].normal_y = transformedCloud->points[i].normal_y;
3570 cloudIWithNormals->points[i].normal_z = transformedCloud->points[i].normal_z;
3571 cloudIWithNormals->points[i].curvature = transformedCloud->points[i].curvature;
3572 int * intensity = (
int *)&cloudIWithNormals->points[i].intensity;
3574 int(transformedCloud->points[i].r) |
3575 int(transformedCloud->points[i].g) << 8 |
3576 int(transformedCloud->points[i].b) << 16 |
3577 int(transformedCloud->points[i].a) << 24;
3582 cloudIWithoutNormals.reset(
new pcl::PointCloud<pcl::PointXYZI>);
3583 cloudIWithoutNormals->resize(transformedCloud->size());
3584 for(
unsigned int i=0; i<cloudIWithoutNormals->size(); ++i)
3586 cloudIWithoutNormals->points[i].x = transformedCloud->points[i].x;
3587 cloudIWithoutNormals->points[i].y = transformedCloud->points[i].y;
3588 cloudIWithoutNormals->points[i].z = transformedCloud->points[i].z;
3589 int * intensity = (
int *)&cloudIWithoutNormals->points[i].intensity;
3591 int(transformedCloud->points[i].r) |
3592 int(transformedCloud->points[i].g) << 8 |
3593 int(transformedCloud->points[i].b) << 16 |
3594 int(transformedCloud->points[i].a) << 24;
3598 else if(
_ui->spinBox_normalKSearch->value()<=0 &&
_ui->doubleSpinBox_normalRadiusSearch->value()<=0.0)
3600 cloudRGBWithoutNormals.reset(
new pcl::PointCloud<pcl::PointXYZRGB>);
3601 pcl::copyPointCloud(*transformedCloud, *cloudRGBWithoutNormals);
3604 QString pathFile = path+QDir::separator()+QString(
"%1%2.%3").arg(prefix).arg(iter->first).arg(suffix);
3605 bool success =
false;
3608 if(cloudIWithNormals.get())
3610 success = pcl::io::savePCDFile(pathFile.toStdString(), *cloudIWithNormals, binaryMode) == 0;
3612 else if(cloudIWithoutNormals.get())
3614 success = pcl::io::savePCDFile(pathFile.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
3616 else if(cloudRGBWithoutNormals.get())
3618 success = pcl::io::savePCDFile(pathFile.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
3622 success = pcl::io::savePCDFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
3625 else if(suffix ==
"ply")
3627 if(cloudIWithNormals.get())
3629 success = pcl::io::savePLYFile(pathFile.toStdString(), *cloudIWithNormals, binaryMode) == 0;
3631 else if(cloudIWithoutNormals.get())
3633 success = pcl::io::savePLYFile(pathFile.toStdString(), *cloudIWithoutNormals, binaryMode) == 0;
3635 else if(cloudRGBWithoutNormals.get())
3637 success = pcl::io::savePLYFile(pathFile.toStdString(), *cloudRGBWithoutNormals, binaryMode) == 0;
3641 success = pcl::io::savePLYFile(pathFile.toStdString(), *transformedCloud, binaryMode) == 0;
3646 UFATAL(
"Extension not recognized! (%s)", suffix.toStdString().c_str());
3650 _progressDialog->
appendText(tr(
"Saved cloud %1 (%2 points) to %3.").arg(iter->first).arg(iter->second->size()).arg(pathFile));
3654 _progressDialog->
appendText(tr(
"Failed saving cloud %1 (%2 points) to %3.").arg(iter->first).arg(iter->second->size()).arg(pathFile), Qt::darkRed);
3663 QApplication::processEvents();
3676 const QString & workingDirectory,
3677 const std::map<int, Transform> & poses,
3678 const std::map<int, pcl::PolygonMesh::Ptr> & meshes,
3681 if(meshes.size() == 1)
3683 QString path = QFileDialog::getSaveFileName(
this, tr(
"Save mesh to ..."), workingDirectory+QDir::separator()+
"mesh.ply", tr(
"Mesh (*.ply)"));
3686 if(meshes.begin()->second->polygons.size())
3689 QApplication::processEvents();
3691 QApplication::processEvents();
3693 bool success =
false;
3694 if(QFileInfo(path).suffix() ==
"")
3699 if(QFileInfo(path).suffix() ==
"ply")
3703 success = pcl::io::savePLYFileBinary(path.toStdString(), *meshes.begin()->second) == 0;
3707 success = pcl::io::savePLYFile(path.toStdString(), *meshes.begin()->second) == 0;
3710 else if(QFileInfo(path).suffix() ==
"obj")
3712 success = pcl::io::saveOBJFile(path.toStdString(), *meshes.begin()->second) == 0;
3716 UERROR(
"Extension not recognized! (%s) Should be (*.ply).", QFileInfo(path).suffix().toStdString().c_str());
3723 QMessageBox::information(
this, tr(
"Save successful!"), tr(
"Mesh saved to \"%1\"").arg(path));
3727 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Failed to save to \"%1\"").arg(path));
3732 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Cloud is empty..."));
3736 else if(meshes.size())
3738 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Save meshes to (*.ply *.obj)..."), workingDirectory, 0);
3743 items.push_back(
"ply");
3744 items.push_back(
"obj");
3745 QString suffix = QInputDialog::getItem(
this, tr(
"File format"), tr(
"Which format?"), items, 0,
false, &ok);
3749 QString prefix = QInputDialog::getText(
this, tr(
"File prefix"), tr(
"Prefix:"), QLineEdit::Normal,
"mesh", &ok);
3753 for(std::map<int, pcl::PolygonMesh::Ptr>::const_iterator iter=meshes.begin(); iter!=meshes.end(); ++iter)
3755 if(iter->second->polygons.size())
3757 pcl::PolygonMesh mesh;
3758 mesh.polygons = iter->second->polygons;
3760 for(
unsigned int i=0; i<iter->second->cloud.fields.size(); ++i)
3762 if(iter->second->cloud.fields[i].name.compare(
"rgb") == 0)
3770 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp(
new pcl::PointCloud<pcl::PointXYZRGB>);
3771 pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
3773 pcl::toPCLPointCloud2(*tmp, mesh.cloud);
3777 pcl::PointCloud<pcl::PointXYZ>::Ptr tmp(
new pcl::PointCloud<pcl::PointXYZ>);
3778 pcl::fromPCLPointCloud2(iter->second->cloud, *tmp);
3780 pcl::toPCLPointCloud2(*tmp, mesh.cloud);
3783 QString pathFile = path+QDir::separator()+QString(
"%1%2.%3").arg(prefix).arg(iter->first).arg(suffix);
3784 bool success =
false;
3789 success = pcl::io::savePLYFileBinary(pathFile.toStdString(), mesh) == 0;
3793 success = pcl::io::savePLYFile(pathFile.toStdString(), mesh) == 0;
3796 else if(suffix ==
"obj")
3798 success = pcl::io::saveOBJFile(pathFile.toStdString(), mesh) == 0;
3802 UFATAL(
"Extension not recognized! (%s)", suffix.toStdString().c_str());
3807 .arg(iter->first).arg(iter->second->polygons.size()).arg(pathFile));
3812 .arg(iter->first).arg(iter->second->polygons.size()).arg(pathFile), Qt::darkRed);
3821 QApplication::processEvents();
3834 const QString & workingDirectory,
3835 const std::map<int, Transform> & poses,
3836 std::map<int, pcl::TextureMesh::Ptr> & meshes,
3837 const QMap<int, Signature> & cachedSignatures,
3838 const std::vector<std::map<int, pcl::PointXY> > & textureVertexToPixels)
3840 std::map<int, cv::Mat> images;
3841 std::map<int, std::vector<CameraModel> > calibrations;
3842 for(QMap<int, Signature>::const_iterator iter=cachedSignatures.constBegin(); iter!=cachedSignatures.constEnd(); ++iter)
3844 std::vector<CameraModel> models;
3845 if(iter->sensorData().cameraModels().size())
3847 models = iter->sensorData().cameraModels();
3849 else if(iter->sensorData().stereoCameraModel().isValidForProjection())
3851 models.push_back(iter->sensorData().stereoCameraModel().left());
3856 if(!iter->sensorData().imageRaw().empty())
3858 calibrations.insert(std::make_pair(iter.key(), models));
3859 images.insert(std::make_pair(iter.key(), iter->sensorData().imageRaw()));
3861 else if(!iter->sensorData().imageCompressed().empty())
3863 calibrations.insert(std::make_pair(iter.key(), models));
3864 images.insert(std::make_pair(iter.key(), iter->sensorData().imageCompressed()));
3868 int textureSize = 1024;
3869 if(
_ui->comboBox_meshingTextureSize->currentIndex() > 0)
3871 textureSize = 128 <<
_ui->comboBox_meshingTextureSize->currentIndex();
3873 int blendingDecimation = 0;
3874 if(
_ui->checkBox_blending->isChecked())
3876 if(
_ui->comboBox_blendingDecimation->currentIndex() > 0)
3878 blendingDecimation = 1 << (
_ui->comboBox_blendingDecimation->currentIndex()-1);
3882 if(meshes.size() == 1)
3884 QString path = QFileDialog::getSaveFileName(
this, tr(
"Save texture mesh to ..."), workingDirectory+QDir::separator()+
"mesh.obj", tr(
"Mesh (*.obj)"));
3887 if(meshes.begin()->second->tex_materials.size())
3889 _progressDialog->
appendText(tr(
"Saving the mesh (with %1 textures)...").arg(meshes.begin()->second->tex_materials.size()));
3890 QApplication::processEvents();
3892 QApplication::processEvents();
3894 bool success =
false;
3895 if(QFileInfo(path).suffix() ==
"")
3900 pcl::TextureMesh::Ptr mesh = meshes.begin()->second;
3902 cv::Mat globalTextures;
3903 bool texturesMerged =
_ui->comboBox_meshingTextureSize->isEnabled() &&
_ui->comboBox_meshingTextureSize->currentIndex() > 0;
3904 if(texturesMerged && mesh->tex_materials.size()>1)
3907 QApplication::processEvents();
3909 QApplication::processEvents();
3911 std::map<int, std::map<int, cv::Vec4d> > gains;
3912 std::map<int, std::map<int, cv::Mat> > blendingGains;
3913 std::pair<float, float> contrastValues(0,0);
3921 _ui->checkBox_multiband->isEnabled() &&
_ui->checkBox_multiband->isChecked()?1:
_ui->spinBox_mesh_maxTextures->value(),
3922 textureVertexToPixels,
3923 _ui->checkBox_gainCompensation->isChecked(),
3924 _ui->doubleSpinBox_gainBeta->value(),
3925 _ui->checkBox_gainRGB->isChecked(),
3926 _ui->checkBox_blending->isChecked(),
3928 _ui->spinBox_textureBrightnessContrastRatioLow->value(),
3929 _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
3930 _ui->checkBox_exposureFusion->isEnabled() &&
_ui->checkBox_exposureFusion->isChecked(),
3938 QApplication::processEvents();
3940 QApplication::processEvents();
3942 if(
_ui->checkBox_multiband->isEnabled() &&
_ui->checkBox_multiband->isChecked() && mesh->tex_polygons.size() == 1)
3945 QApplication::processEvents();
3947 QApplication::processEvents();
3952 mesh->tex_polygons[0],
3954 textureVertexToPixels,
3960 _ui->comboBox_meshingTextureFormat->currentText().toStdString(),
3969 QMessageBox::information(
this, tr(
"Save successful!"), tr(
"Mesh saved to \"%1\"").arg(path));
3973 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Failed to save to \"%1\"").arg(path));
3979 bool singleTexture = mesh->tex_materials.size() == 1;
3982 removeDirRecursively(QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName());
3983 QDir(QFileInfo(path).absoluteDir().absolutePath()).mkdir(QFileInfo(path).baseName());
3987 cv::Mat previousImage;
3988 int previousTextureId = 0;
3989 std::vector<CameraModel> previousCameraModels;
3992 for(
unsigned int i=0; i<mesh->tex_materials.size(); ++i)
3994 if(!mesh->tex_materials[i].tex_file.empty())
4000 fullPath = QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName()+
_ui->comboBox_meshingTextureFormat->currentText();
4004 fullPath = QFileInfo(path).absoluteDir().absolutePath()+QDir::separator()+QFileInfo(path).baseName()+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText();
4006 UDEBUG(
"Saving %s...", fullPath.toStdString().c_str());
4007 if(singleTexture || !QFileInfo(fullPath).exists())
4009 std::list<std::string> texFileSplit =
uSplit(mesh->tex_materials[i].tex_file,
'_');
4010 if(texFileSplit.size() &&
uIsInteger(texFileSplit.front(),
false))
4012 int textureId =
uStr2Int(texFileSplit.front());
4013 int textureSubCamera = -1;
4014 if(texFileSplit.size() == 2 &&
4017 textureSubCamera =
uStr2Int(texFileSplit.back());
4020 std::vector<CameraModel> cameraModels;
4022 if(textureId == previousTextureId)
4024 image = previousImage;
4025 cameraModels = previousCameraModels;
4029 if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
4031 cachedSignatures.value(textureId).sensorData().uncompressDataConst(&image, 0);
4032 cameraModels = cachedSignatures.value(textureId).sensorData().cameraModels();
4043 previousImage = image;
4044 previousCameraModels = cameraModels;
4045 previousTextureId = textureId;
4048 imageSize = image.size();
4049 if(textureSubCamera>=0)
4052 imageSize.width/=cameraModels.size();
4053 image = image.colRange(imageSize.width*textureSubCamera, imageSize.width*(textureSubCamera+1));
4060 if(!cv::imwrite(fullPath.toStdString(), image))
4063 .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
4067 else if(imageSize.height && imageSize.width)
4070 cv::Mat image = cv::Mat::ones(imageSize, CV_8UC1)*255;
4071 cv::imwrite(fullPath.toStdString(), image);
4073 else if(!globalTextures.empty())
4075 if(!cv::imwrite(fullPath.toStdString(), globalTextures(
cv::Range::all(), cv::Range(i*globalTextures.rows, (i+1)*globalTextures.rows))))
4078 .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
4084 UWARN(
"Ignored texture %s (no image size set yet)", mesh->tex_materials[i].tex_file.c_str());
4089 UWARN(
"File %s already exists!", fullPath.toStdString().c_str());
4094 mesh->tex_materials[i].tex_file=QFileInfo(path).baseName().toStdString()+
_ui->comboBox_meshingTextureFormat->currentText().toStdString();
4098 mesh->tex_materials[i].tex_file=(QFileInfo(path).baseName()+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
4103 success = pcl::io::saveOBJFile(path.toStdString(), *mesh) == 0;
4109 QMessageBox::information(
this, tr(
"Save successful!"), tr(
"Mesh saved to \"%1\"").arg(path));
4113 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"Failed to save to \"%1\"").arg(path));
4118 QMessageBox::warning(
this, tr(
"Save failed!"), tr(
"No textures..."));
4122 else if(meshes.size())
4124 QString path = QFileDialog::getExistingDirectory(
this, tr(
"Save texture meshes to (*.obj)..."), workingDirectory, 0);
4128 QString prefix = QInputDialog::getText(
this, tr(
"File prefix"), tr(
"Prefix:"), QLineEdit::Normal,
"mesh", &ok);
4129 QString suffix =
"obj";
4133 for(std::map<int, pcl::TextureMesh::Ptr>::iterator iter=meshes.begin(); iter!=meshes.end(); ++iter)
4135 QString currentPrefix=prefix+QString::number(iter->first);
4136 if(iter->second->tex_materials.size())
4138 pcl::TextureMesh::Ptr mesh = iter->second;
4139 cv::Mat globalTextures;
4140 bool texturesMerged =
_ui->comboBox_meshingTextureSize->isEnabled() &&
_ui->comboBox_meshingTextureSize->currentIndex() > 0;
4141 if(texturesMerged && mesh->tex_materials.size()>1)
4150 _ui->spinBox_mesh_maxTextures->value(),
4151 textureVertexToPixels,
4152 _ui->checkBox_gainCompensation->isChecked(),
4153 _ui->doubleSpinBox_gainBeta->value(),
4154 _ui->checkBox_gainRGB->isChecked(),
4155 _ui->checkBox_blending->isChecked(),
4157 _ui->spinBox_textureBrightnessContrastRatioLow->value(),
4158 _ui->spinBox_textureBrightnessContrastRatioHigh->value(),
4159 _ui->checkBox_exposureFusion->isEnabled() &&
_ui->checkBox_exposureFusion->isChecked());
4161 bool singleTexture = mesh->tex_materials.size() == 1;
4165 QDir(path).mkdir(currentPrefix);
4169 cv::Mat previousImage;
4170 int previousTextureId = 0;
4171 std::vector<CameraModel> previousCameraModels;
4174 for(
unsigned int i=0;i<mesh->tex_materials.size(); ++i)
4176 if(!mesh->tex_materials[i].tex_file.empty())
4178 std::list<std::string> texFileSplit =
uSplit(mesh->tex_materials[i].tex_file,
'_');
4180 int textureSubCamera = -1;
4181 if(texFileSplit.size() &&
uIsInteger(texFileSplit.front(),
false))
4183 textureId =
uStr2Int(texFileSplit.front());
4184 if(texFileSplit.size() == 2 &&
4187 textureSubCamera =
uStr2Int(texFileSplit.back());
4195 mesh->tex_materials[i].tex_file =
uNumber2Str(iter->first);
4196 fullPath = path+QDir::separator()+prefix + QString(mesh->tex_materials[i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText();
4200 fullPath = path+QDir::separator()+currentPrefix+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText();
4205 std::vector<CameraModel> cameraModels;
4207 if(textureId == previousTextureId)
4209 image = previousImage;
4210 cameraModels = previousCameraModels;
4214 if(cachedSignatures.contains(textureId) && !cachedSignatures.value(textureId).sensorData().imageCompressed().empty())
4216 cachedSignatures.value(textureId).sensorData().uncompressDataConst(&image, 0);
4217 cameraModels = cachedSignatures.value(textureId).sensorData().cameraModels();
4228 previousImage = image;
4229 previousCameraModels = cameraModels;
4230 previousTextureId = textureId;
4235 imageSize = image.size();
4236 if(textureSubCamera>=0)
4239 imageSize.width/=cameraModels.size();
4240 image = image.colRange(imageSize.width*textureSubCamera, imageSize.width*(textureSubCamera+1));
4247 if(!cv::imwrite(fullPath.toStdString(), image))
4250 .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
4254 else if(imageSize.height && imageSize.width)
4257 cv::Mat image = cv::Mat::ones(imageSize, CV_8UC1)*255;
4258 cv::imwrite(fullPath.toStdString(), image);
4260 else if(!globalTextures.empty())
4262 if(!cv::imwrite(fullPath.toStdString(), globalTextures(
cv::Range::all(), cv::Range(i*globalTextures.rows, (i+1)*globalTextures.rows))))
4265 .arg(mesh->tex_materials[i].tex_file.c_str()).arg(fullPath), Qt::darkRed);
4271 UWARN(
"Ignored texture %s (no image size set yet)", mesh->tex_materials[i].tex_file.c_str());
4276 mesh->tex_materials[i].tex_file=(prefix+ QString(mesh->tex_materials[i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
4280 mesh->tex_materials[i].tex_file=(currentPrefix+QDir::separator()+QString(mesh->tex_materials[i].tex_file.c_str())+
_ui->comboBox_meshingTextureFormat->currentText()).toStdString();
4284 pcl::PointCloud<pcl::PointNormal>::Ptr tmp(
new pcl::PointCloud<pcl::PointNormal>);
4285 pcl::fromPCLPointCloud2(mesh->cloud, *tmp);
4287 pcl::toPCLPointCloud2(*tmp, mesh->cloud);
4289 QString pathFile = path+QDir::separator()+QString(
"%1.%3").arg(currentPrefix).arg(suffix);
4290 bool success =
false;
4293 success = pcl::io::saveOBJFile(pathFile.toStdString(), *mesh) == 0;
4297 UFATAL(
"Extension not recognized! (%s)", suffix.toStdString().c_str());
4302 .arg(iter->first).arg(mesh->tex_materials.size()).arg(pathFile));
4307 .arg(iter->first).arg(mesh->tex_materials.size()).arg(pathFile), Qt::darkRed);
4316 QApplication::processEvents();
bool uIsInteger(const std::string &str, bool checkForSign=true)
void setDefaultBackgroundColor(const QColor &color)
int UTILITE_EXP uStr2Int(const std::string &str)
pcl::PolygonMesh::Ptr chiselToPolygonMesh(const chisel::MeshMap &meshMap, unsigned char r=100, unsigned char g=100, unsigned char b=100)
ProgressDialog * _progressDialog
void setAutoClose(bool on, int delayedClosingTimeMsec=-1)
void incrementStep(int steps=1)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP subtractFiltering(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, float radiusSearch, int minNeighborsInRadius=1)
void uncompressDataConst(cv::Mat *imageRaw, cv::Mat *depthOrRightRaw, LaserScan *laserScanRaw=0, cv::Mat *userDataRaw=0, cv::Mat *groundCellsRaw=0, cv::Mat *obstacleCellsRaw=0, cv::Mat *emptyCellsRaw=0) const
int getMaxTextures() const
pcl::TextureMesh::Ptr RTABMAP_EXP concatenateTextureMeshes(const std::list< pcl::TextureMesh::Ptr > &meshes)
std::shared_ptr< chisel::ColorImage< unsigned char > > colorImageToChisel(const cv::Mat &image)
std::map< int, Transform > RTABMAP_EXP radiusPosesFiltering(const std::map< int, Transform > &poses, float radius, float angle, bool keepLatest=true)
cv::Mat RTABMAP_EXP cvtDepthToFloat(const cv::Mat &depth16U)
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
void setCancelButtonVisible(bool visible)
int getBlendingDecimation() const
const LaserScan & laserScanCompressed() const
std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr, pcl::IndicesPtr > > getClouds(const std::map< int, Transform > &poses, const QMap< int, Signature > &cachedSignatures, const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > &cachedClouds, const std::map< int, LaserScan > &cachedScans, const ParametersMap ¶meters, bool &has2dScans) const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
void updateMLSGrpVisibility()
pcl::IndicesPtr RTABMAP_EXP passThrough(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
bool isGainCompensation() const
void RTABMAP_EXP getMinMax3D(const cv::Mat &laserScan, cv::Point3f &min, cv::Point3f &max)
std::vector< pcl::Vertices > RTABMAP_EXP filterCloseVerticesFromMesh(const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr cloud, const std::vector< pcl::Vertices > &polygons, float radius, float angle, bool keepLatestInRadius)
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP laserScanToPointCloudRGBNormal(const LaserScan &laserScan, const Transform &transform=Transform(), unsigned char r=100, unsigned char g=100, unsigned char b=100)
std::vector< int > RTABMAP_EXP filterNotUsedVerticesFromMesh(const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGBNormal > &outputCloud, std::vector< pcl::Vertices > &outputPolygons)
bool RTABMAP_EXP multiBandTexturing(const std::string &outputOBJPath, const pcl::PCLPointCloud2 &cloud, const std::vector< pcl::Vertices > &polygons, const std::map< int, Transform > &cameraPoses, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels, const std::map< int, cv::Mat > &images, const std::map< int, std::vector< CameraModel > > &cameraModels, const Memory *memory=0, const DBDriver *dbDriver=0, int textureSize=8192, const std::string &textureFormat="jpg", const std::map< int, std::map< int, cv::Vec4d > > &gains=std::map< int, std::map< int, cv::Vec4d > >(), const std::map< int, std::map< int, cv::Mat > > &blendingGains=std::map< int, std::map< int, cv::Mat > >(), const std::pair< float, float > &contrastValues=std::pair< float, float >(0, 0), bool gainRGB=true)
chisel::PinholeCamera cameraModelToChiselCamera(const CameraModel &camera)
std::set< K > uKeysSet(const std::map< K, V > &m)
std::list< V > uValuesList(const std::multimap< K, V > &mm)
float UTILITE_EXP uStr2Float(const std::string &str)
GLM_FUNC_DECL bool all(vecType< bool, P > const &v)
static const float vertices[]
void setRGBDImage(const cv::Mat &rgb, const cv::Mat &depth, const CameraModel &model, bool clearPreviousData=true)
void viewClouds(const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, const std::map< int, int > &mapIds, const QMap< int, Signature > &cachedSignatures, const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > &cachedClouds, const std::map< int, LaserScan > &cachedScans, const QString &workingDirectory, const ParametersMap ¶meters)
void getNodeData(int signatureId, SensorData &data, bool images=true, bool scan=true, bool userData=true, bool occupancyGrid=true) const
bool getExportedClouds(const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, const std::map< int, int > &mapIds, const QMap< int, Signature > &cachedSignatures, const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > &cachedClouds, const std::map< int, LaserScan > &cachedScans, const QString &workingDirectory, const ParametersMap ¶meters, std::map< int, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr > &clouds, std::map< int, pcl::PolygonMesh::Ptr > &meshes, std::map< int, pcl::TextureMesh::Ptr > &textureMeshes, std::vector< std::map< int, pcl::PointXY > > &textureVertexToPixels)
std::map< std::string, std::string > ParametersMap
cv::Mat RTABMAP_EXP fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
void setLighting(bool on)
Basic mathematics functions.
Some conversion functions.
void setPolygonPicking(bool enabled)
const LaserScan & laserScanRaw() const
void buildPickingLocator(bool enable)
const cv::Mat & imageRaw() const
double getGain(int id, double *r=0, double *g=0, double *b=0) const
pcl::IndicesPtr RTABMAP_EXP extractIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
bool addCloudTextureMesh(const std::string &id, const pcl::TextureMesh::Ptr &textureMesh, const cv::Mat &texture, const Transform &pose=Transform::getIdentity())
void saveClouds(const QString &workingDirectory, const std::map< int, Transform > &poses, const std::map< int, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr > &clouds, bool binaryMode=true)
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
void setIntensityRedColormap(bool value)
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_EXP mls(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float searchRadius=0.0f, int polygonialOrder=2, int upsamplingMethod=0, float upsamplingRadius=0.0f, float upsamplingStep=0.0f, int pointDensity=0, float dilationVoxelSize=1.0f, int dilationIterations=0)
#define UASSERT(condition)
Wrappers of STL for convenient functions.
void getWeight(int signatureId, int &weight) const
bool getLaserScanInfo(int signatureId, LaserScan &info) const
bool isValidForProjection() const
const CameraModel & left() const
std::list< std::list< int > > RTABMAP_EXP clusterPolygons(const std::vector< std::set< int > > &neighborPolygons, int minClusterSize=0)
LaserScan RTABMAP_EXP commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, float groundNormalsUp=0.0f)
T uMax3(const T &a, const T &b, const T &c)
void saveTextureMeshes(const QString &workingDirectory, const std::map< int, Transform > &poses, std::map< int, pcl::TextureMesh::Ptr > &textureMeshes, const QMap< int, Signature > &cachedSignatures, const std::vector< std::map< int, pcl::PointXY > > &textureVertexToPixels)
void RTABMAP_EXP appendMesh(pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudA, std::vector< pcl::Vertices > &polygonsA, const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudB, const std::vector< pcl::Vertices > &polygonsB)
#define UASSERT_MSG(condition, msg_str)
int getTextureBrightnessConstrastRatioHigh() const
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
chisel::PointCloudPtr pointCloudRGBToChisel(const typename pcl::PointCloud< PointRGBT > &cloud, const Transform &transform=Transform::getIdentity())
void setCloudPointSize(const std::string &id, int size)
bool getCalibration(int signatureId, std::vector< CameraModel > &models, StereoCameraModel &stereoModel) const
bool isExposeFusion() const
QString _workingDirectory
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
void setMaximumSteps(int steps)
Transform localTransform() const
const cv::Mat & depthOrRightRaw() const
double getGainBeta() const
pcl::PolygonMesh::Ptr RTABMAP_EXP createMesh(const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloudWithNormals, float gp3SearchRadius=0.025, float gp3Mu=2.5, int gp3MaximumNearestNeighbors=100, float gp3MaximumSurfaceAngle=M_PI/4, float gp3MinimumAngle=M_PI/18, float gp3MaximumAngle=2 *M_PI/3, bool gp3NormalConsistency=true)
std::vector< pcl::Vertices > RTABMAP_EXP organizedFastMesh(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, double angleTolerance, bool quad, int trianglePixelSize, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0))
ExportCloudsDialog(QWidget *parent=0)
void setProgressDialogToMax()
bool uContains(const std::list< V > &list, const V &value)
void load(const std::string &path)
void exportClouds(const std::map< int, Transform > &poses, const std::multimap< int, Link > &links, const std::map< int, int > &mapIds, const QMap< int, Signature > &cachedSignatures, const std::map< int, std::pair< pcl::PointCloud< pcl::PointXYZRGB >::Ptr, pcl::IndicesPtr > > &cachedClouds, const std::map< int, LaserScan > &cachedScans, const QString &workingDirectory, const ParametersMap ¶meters)
void apply(int id, pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, bool rgb=true) const
bool getNodeInfo(int signatureId, Transform &pose, int &mapId, int &weight, std::string &label, double &stamp, Transform &groundTruthPose, std::vector< float > &velocity, GPS &gps, EnvSensors &sensors) const
cv::Mat RTABMAP_EXP mergeTextures(pcl::TextureMesh &mesh, const std::map< int, cv::Mat > &images, const std::map< int, CameraModel > &calibrations, const Memory *memory=0, const DBDriver *dbDriver=0, int textureSize=4096, int textureCount=1, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels=std::vector< std::map< int, pcl::PointXY > >(), bool gainCompensation=true, float gainBeta=10.0f, bool gainRGB=true, bool blending=true, int blendingDecimation=0, int brightnessContrastRatioLow=0, int brightnessContrastRatioHigh=0, bool exposureFusion=false, const ProgressState *state=0, unsigned char blankValue=255, std::map< int, std::map< int, cv::Vec4d > > *gains=0, std::map< int, std::map< int, cv::Mat > > *blendingGains=0, std::pair< float, float > *contrastValues=0)
bool addCloud(const std::string &id, const pcl::PCLPointCloud2Ptr &binaryCloud, const Transform &pose, bool rgb, bool hasNormals, bool hasIntensity, const QColor &color=QColor(), int viewport=1)
void uSleep(unsigned int ms)
void RTABMAP_EXP adjustNormalsToViewPoints(const std::map< int, Transform > &poses, const pcl::PointCloud< pcl::PointXYZ >::Ptr &rawCloud, const std::vector< int > &rawCameraIndices, pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
pcl::IndicesPtr RTABMAP_EXP radiusFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(const pcl::PolygonMesh::Ptr &mesh, const std::map< int, Transform > &poses, const std::map< int, CameraModel > &cameraModels, const std::map< int, cv::Mat > &cameraDepths, float maxDistance=0.0f, float maxDepthError=0.0f, float maxAngle=0.0f, int minClusterSize=50, const std::vector< float > &roiRatios=std::vector< float >(), const ProgressState *state=0, std::vector< std::map< int, pcl::PointXY > > *vertexToPixels=0, bool distanceToCamPolicy=false)
const std::vector< CameraModel > & cameraModels() const
std::vector< pcl::Vertices > RTABMAP_EXP filterInvalidPolygons(const std::vector< pcl::Vertices > &polygons)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
SensorData & sensorData()
void RTABMAP_EXP cleanTextureMesh(pcl::TextureMesh &textureMesh, int minClusterSize)
Ui_ExportCloudsDialog * _ui
void undistort(cv::Mat &depth) const
void updateReconstructionFlavor()
void RTABMAP_EXP createPolygonIndexes(const std::vector< pcl::Vertices > &polygons, int cloudSize, std::vector< std::set< int > > &neighborPolygons, std::vector< std::set< int > > &vertexPolygons)
Given a set of polygons, create two indexes: polygons to neighbor polygons and vertices to polygons...
cv::Mat RTABMAP_EXP fillDepthHoles(const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
ULogger class and convenient macros.
const StereoCameraModel & stereoCameraModel() const
void setBackfaceCulling(bool enabled, bool frontfaceCulling)
void feed(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloudA, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloudB, const Transform &transformB)
void saveMeshes(const QString &workingDirectory, const std::map< int, Transform > &poses, const std::map< int, pcl::PolygonMesh::Ptr > &meshes, bool binaryMode=true)
const cv::Mat & imageCompressed() const
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
void forceAssembling(bool enabled)
int getTextureSize() const
std::map< EnvSensor::Type, EnvSensor > EnvSensors
bool addCloudMesh(const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const std::vector< pcl::Vertices > &polygons, const Transform &pose=Transform::getIdentity())
const DBDriver * _dbDriver
float RTABMAP_EXP getDepth(const cv::Mat &depthImage, float x, float y, bool smoothing, float depthErrorRatio=0.02f, bool estWithNeighborsIfNull=false)
int getIndex(int id) const
void appendText(const QString &text, const QColor &color=Qt::black)
static bool removeDirRecursively(const QString &dirName)
void selectDistortionModel()
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
int getTextureBrightnessConstrastRatioLow() const
const Transform & localTransform() const
std::string UTILITE_EXP uFormat(const char *fmt,...)
std::string UTILITE_EXP uNumber2Str(unsigned int number)
virtual ~ExportCloudsDialog()
CameraModel scaled(double scale) const
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())
std::shared_ptr< chisel::DepthImage< float > > depthImageToChisel(const cv::Mat &image)
void setIntensityRainbowColormap(bool value)
GainCompensator * _compensator