28 #ifndef UTIL3D_SURFACE_H_
29 #define UTIL3D_SURFACE_H_
31 #include <rtabmap/core/rtabmap_core_export.h>
33 #include <pcl/PolygonMesh.h>
34 #include <pcl/point_cloud.h>
35 #include <pcl/point_types.h>
36 #include <pcl/TextureMesh.h>
37 #include <pcl/pcl_base.h>
42 #include <rtabmap/core/Version.h>
65 const std::vector<pcl::Vertices> & polygons,
67 std::vector<std::set<int> > & neighborPolygons,
68 std::vector<std::set<int> > & vertexPolygons);
71 const std::vector<std::set<int> > & neighborPolygons,
72 int minClusterSize = 0);
75 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
76 double angleTolerance,
78 int trianglePixelSize,
79 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
81 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
82 double angleTolerance =
M_PI/16,
84 int trianglePixelSize = 2,
85 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
87 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
88 double angleTolerance =
M_PI/16,
90 int trianglePixelSize = 2,
91 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
94 pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudA,
95 std::vector<pcl::Vertices> & polygonsA,
96 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudB,
97 const std::vector<pcl::Vertices> & polygonsB);
99 pcl::PointCloud<pcl::PointXYZRGB> & cloudA,
100 std::vector<pcl::Vertices> & polygonsA,
101 const pcl::PointCloud<pcl::PointXYZRGB> & cloudB,
102 const std::vector<pcl::Vertices> & polygonsB);
106 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
107 const std::vector<pcl::Vertices> & polygons,
108 pcl::PointCloud<pcl::PointXYZRGBNormal> & outputCloud,
109 std::vector<pcl::Vertices> & outputPolygons);
111 const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
112 const std::vector<pcl::Vertices> & polygons,
113 pcl::PointCloud<pcl::PointXYZRGB> & outputCloud,
114 std::vector<pcl::Vertices> & outputPolygons);
116 const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
117 const std::vector<pcl::Vertices> & polygons,
118 pcl::PointCloud<pcl::PointXYZRGB> & outputCloud,
119 std::vector<pcl::Vertices> & outputPolygons);
122 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud,
123 const std::vector<pcl::Vertices> & polygons,
126 bool keepLatestInRadius);
129 const std::vector<pcl::Vertices> & polygons);
131 pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT
createMesh(
132 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloudWithNormals,
133 float gp3SearchRadius = 0.025,
135 int gp3MaximumNearestNeighbors = 100,
136 float gp3MaximumSurfaceAngle =
M_PI/4,
137 float gp3MinimumAngle =
M_PI/18,
138 float gp3MaximumAngle = 2*
M_PI/3,
139 bool gp3NormalConsistency =
true);
142 const pcl::PolygonMesh::Ptr & mesh,
143 const std::map<int, Transform> & poses,
144 const std::map<int, CameraModel> & cameraModels,
145 const std::map<int, cv::Mat> & cameraDepths,
146 float maxDistance = 0.0f,
148 float maxAngle = 0.0f,
149 int minClusterSize = 50,
150 const std::vector<float> & roiRatios = std::vector<float>(),
151 const ProgressState *
state = 0,
152 std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0,
153 bool distanceToCamPolicy =
false);
155 const pcl::PolygonMesh::Ptr & mesh,
156 const std::map<int, Transform> & poses,
157 const std::map<
int, std::vector<CameraModel> > & cameraModels,
158 const std::map<int, cv::Mat> & cameraDepths,
159 float maxDistance = 0.0f,
161 float maxAngle = 0.0f,
162 int minClusterSize = 50,
163 const std::vector<float> & roiRatios = std::vector<float>(),
164 const ProgressState *
state = 0,
165 std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0,
166 bool distanceToCamPolicy =
false);
172 pcl::TextureMesh & textureMesh,
176 const std::list<pcl::TextureMesh::Ptr> & meshes);
179 pcl::TextureMesh & mesh,
const cv::Size & imageSize,
int textureSize,
int maxTextures,
float & scale, std::vector<bool> * materialsKept=0);
182 const std::vector<pcl::Vertices> & polygons);
184 const std::vector<std::vector<pcl::Vertices> > & polygons);
186 const std::vector<std::vector<RTABMAP_PCL_INDEX> > & polygons);
188 const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & tex_polygons);
191 const cv::Mat & cloudMat,
192 const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & polygons,
193 #
if PCL_VERSION_COMPARE(>=, 1, 8, 0)
196 const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
202 const cv::Mat & cloudMat,
203 const std::vector<std::vector<RTABMAP_PCL_INDEX> > & polygons);
210 pcl::TextureMesh & mesh,
211 const std::map<int, cv::Mat> & images,
212 const std::map<int, CameraModel> & calibrations,
213 const Memory * memory = 0,
214 const DBDriver * dbDriver = 0,
215 int textureSize = 4096,
216 int textureCount = 1,
217 const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels = std::vector<std::map<int, pcl::PointXY> >(),
218 bool gainCompensation =
true,
219 float gainBeta = 10.0f,
221 bool blending =
true,
222 int blendingDecimation = 0,
223 int brightnessContrastRatioLow = 0,
224 int brightnessContrastRatioHigh = 0,
226 const ProgressState *
state = 0,
227 unsigned char blankValue = 255,
228 std::map<
int, std::map<int, cv::Vec4d> > * gains = 0,
229 std::map<
int, std::map<int, cv::Mat> > * blendingGains = 0,
230 std::pair<float, float> * contrastValues = 0);
232 pcl::TextureMesh & mesh,
233 const std::map<int, cv::Mat> & images,
234 const std::map<
int, std::vector<CameraModel> > & calibrations,
235 const Memory * memory = 0,
236 const DBDriver * dbDriver = 0,
237 int textureSize = 4096,
238 int textureCount = 1,
239 const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels = std::vector<std::map<int, pcl::PointXY> >(),
240 bool gainCompensation =
true,
241 float gainBeta = 10.0f,
243 bool blending =
true,
244 int blendingDecimation = 0,
245 int brightnessContrastRatioLow = 0,
246 int brightnessContrastRatioHigh = 0,
248 const ProgressState *
state = 0,
249 unsigned char blankValue = 255,
250 std::map<
int, std::map<int, cv::Vec4d> > * gains = 0,
251 std::map<
int, std::map<int, cv::Mat> > * blendingGains = 0,
252 std::pair<float, float> * contrastValues = 0);
258 const std::string & outputOBJPath,
259 const pcl::PCLPointCloud2 & cloud,
260 const std::vector<pcl::Vertices> & polygons,
261 const std::map<int, Transform> & cameraPoses,
262 const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels,
263 const std::map<int, cv::Mat> & images,
264 const std::map<
int, std::vector<CameraModel> > & cameraModels,
265 const Memory * memory = 0,
266 const DBDriver * dbDriver = 0,
267 int textureSize = 8192,
268 const std::string & textureFormat =
"jpg",
269 const std::map<
int, std::map<int, cv::Vec4d> > & gains = std::map<
int, std::map<int, cv::Vec4d> >(),
270 const std::map<
int, std::map<int, cv::Mat> > & blendingGains = std::map<
int, std::map<int, cv::Mat> >(),
271 const std::pair<float, float> & contrastValues = std::pair<float, float>(0,0),
272 bool gainRGB =
true);
301 const std::string & outputOBJPath,
302 const pcl::PCLPointCloud2 & cloud,
303 const std::vector<pcl::Vertices> & polygons,
304 const std::map<int, Transform> & cameraPoses,
305 const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels,
306 const std::map<int, cv::Mat> & images,
307 const std::map<
int, std::vector<CameraModel> > & cameraModels,
308 const Memory * memory = 0,
309 const DBDriver * dbDriver = 0,
310 unsigned int textureSize = 8192,
311 unsigned int textureDownscale = 2,
312 const std::string & nbContrib =
"1 5 10 0",
313 const std::string & textureFormat =
"jpg",
314 const std::map<
int, std::map<int, cv::Vec4d> > & gains = std::map<
int, std::map<int, cv::Vec4d> >(),
315 const std::map<
int, std::map<int, cv::Mat> > & blendingGains = std::map<
int, std::map<int, cv::Mat> >(),
316 const std::pair<float, float> & contrastValues = std::pair<float, float>(0,0),
318 unsigned int unwrapMethod = 0,
319 bool fillHoles =
false,
320 unsigned int padding = 5,
321 double bestScoreThreshold = 0.1,
322 double angleHardThreshold = 90.0,
323 bool forceVisibleByAllVertices =
false);
326 const cv::Mat & laserScan,
329 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT
computeNormals(
330 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
332 float searchRadius = 0.0f,
333 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
334 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT
computeNormals(
335 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
337 float searchRadius = 0.0f,
338 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
339 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT
computeNormals(
340 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
342 float searchRadius = 0.0f,
343 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
344 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT
computeNormals(
345 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
346 const pcl::IndicesPtr & indices,
348 float searchRadius = 0.0f,
349 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
350 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT
computeNormals(
351 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
352 const pcl::IndicesPtr & indices,
354 float searchRadius = 0.0f,
355 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
356 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT
computeNormals(
357 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
358 const pcl::IndicesPtr & indices,
360 float searchRadius = 0.0f,
361 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
364 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
366 float searchRadius = 0.0f,
367 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
369 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
371 float searchRadius = 0.0f,
372 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
374 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
376 float searchRadius = 0.0f,
377 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
379 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
381 float searchRadius = 0.0f,
382 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
385 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
386 float maxDepthChangeFactor = 0.02f,
387 float normalSmoothingSize = 10.0f,
388 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
390 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
391 const pcl::IndicesPtr & indices,
392 float maxDepthChangeFactor = 0.02f,
393 float normalSmoothingSize = 10.0f,
394 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
397 const LaserScan & scan,
399 cv::Mat * pcaEigenVectors = 0,
400 cv::Mat * pcaEigenValues = 0);
402 const pcl::PointCloud<pcl::Normal> & normals,
405 cv::Mat * pcaEigenVectors = 0,
406 cv::Mat * pcaEigenValues = 0);
408 const pcl::PointCloud<pcl::PointNormal> & cloud,
411 cv::Mat * pcaEigenVectors = 0,
412 cv::Mat * pcaEigenValues = 0);
414 const pcl::PointCloud<pcl::PointXYZINormal> & cloud,
417 cv::Mat * pcaEigenVectors = 0,
418 cv::Mat * pcaEigenValues = 0);
420 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
423 cv::Mat * pcaEigenVectors = 0,
424 cv::Mat * pcaEigenValues = 0);
426 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT
mls(
427 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
428 float searchRadius = 0.0f,
429 int polygonialOrder = 2,
430 int upsamplingMethod = 0,
431 float upsamplingRadius = 0.0f,
432 float upsamplingStep = 0.0f,
433 int pointDensity = 0,
434 float dilationVoxelSize = 1.0f,
435 int dilationIterations = 0);
436 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT
mls(
437 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
438 const pcl::IndicesPtr & indices,
439 float searchRadius = 0.0f,
440 int polygonialOrder = 2,
441 int upsamplingMethod = 0,
442 float upsamplingRadius = 0.0f,
443 float upsamplingStep = 0.0f,
444 int pointDensity = 0,
445 float dilationVoxelSize = 1.0f,
446 int dilationIterations = 0);
450 const LaserScan & scan,
451 const Eigen::Vector3f & viewpoint,
452 bool forceGroundNormalsUp);
454 const LaserScan & scan,
455 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
456 float groundNormalsUp = 0.0f);
459 pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
460 const Eigen::Vector3f & viewpoint,
461 bool forceGroundNormalsUp);
463 pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
464 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
465 float groundNormalsUp = 0.0f);
468 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
469 const Eigen::Vector3f & viewpoint,
470 bool forceGroundNormalsUp);
472 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
473 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
474 float groundNormalsUp = 0.0f);
477 pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
478 const Eigen::Vector3f & viewpoint,
479 bool forceGroundNormalsUp);
481 pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
482 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
483 float groundNormalsUp = 0.0f);
486 const std::map<int, Transform> & poses,
487 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
488 const std::vector<int> & rawCameraIndices,
489 pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
490 float groundNormalsUp = 0.0f);
492 const std::map<int, Transform> & poses,
493 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
494 const std::vector<int> & rawCameraIndices,
495 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
496 float groundNormalsUp = 0.0f);
498 const std::map<int, Transform> & poses,
499 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
500 const std::vector<int> & rawCameraIndices,
501 pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
502 float groundNormalsUp = 0.0f);
505 const std::map<int, Transform> & viewpoints,
506 const LaserScan & rawScan,
507 const std::vector<int> & viewpointIds,
509 float groundNormalsUp = 0.0f);
511 pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT
meshDecimation(
const pcl::PolygonMesh::Ptr & mesh,
float factor);
513 template<
typename po
intT>
515 const pcl::PointCloud<pointT> & cloud,
516 const std::vector<pcl::Vertices> & polygons,
517 const pcl::PointXYZ & viewPoint = pcl::PointXYZ(0,0,0));
519 template<
typename po
intRGBT>
521 pcl::PolygonMeshPtr & mesh,
522 float meshDecimationFactor = 0.0f,
523 int maximumPolygons = 0,
524 const typename pcl::PointCloud<pointRGBT>::Ptr & cloud = pcl::PointCloud<pointRGBT>::Ptr(),
525 float transferColorRadius = 0.05f,
526 bool coloredOutput =
true,
527 bool cleanMesh =
true,
528 int minClusterSize = 50,
529 ProgressState * progressState = 0);
554 const Eigen::Vector3f & p,
555 const Eigen::Vector3f & dir,
556 const Eigen::Vector3f & v0,
557 const Eigen::Vector3f & v1,
558 const Eigen::Vector3f & v2,
560 Eigen::Vector3f & normal);
562 template<
typename Po
intT>
564 const Eigen::Vector3f & origin,
565 const Eigen::Vector3f & dir,
566 const typename pcl::PointCloud<PointT> & cloud,
567 const std::vector<pcl::Vertices> & polygons,
568 bool ignoreBackFaces,
570 Eigen::Vector3f & normal,