28 #ifndef UTIL3D_SURFACE_H_ 29 #define UTIL3D_SURFACE_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);
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)
194 const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
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);
257 const std::string & outputOBJPath,
258 const pcl::PCLPointCloud2 & cloud,
259 const std::vector<pcl::Vertices> & polygons,
260 const std::map<int, Transform> & cameraPoses,
261 const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels,
262 const std::map<int, cv::Mat> & images,
263 const std::map<
int, std::vector<CameraModel> > & cameraModels,
264 const Memory * memory = 0,
265 const DBDriver * dbDriver = 0,
266 int textureSize = 8192,
267 const std::string & textureFormat =
"jpg",
268 const std::map<
int, std::map<int, cv::Vec4d> > & gains = std::map<
int, std::map<int, cv::Vec4d> >(),
269 const std::map<
int, std::map<int, cv::Mat> > & blendingGains = std::map<
int, std::map<int, cv::Mat> >(),
270 const std::pair<float, float> & contrastValues = std::pair<float, float>(0,0),
271 bool gainRGB =
true),
"Use the same method with 22 parameters instead.");
300 const std::string & outputOBJPath,
301 const pcl::PCLPointCloud2 & cloud,
302 const std::vector<pcl::Vertices> & polygons,
303 const std::map<int, Transform> & cameraPoses,
304 const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels,
305 const std::map<int, cv::Mat> & images,
306 const std::map<
int, std::vector<CameraModel> > & cameraModels,
307 const Memory * memory = 0,
308 const DBDriver * dbDriver = 0,
309 unsigned int textureSize = 8192,
310 unsigned int textureDownscale = 2,
311 const std::string & nbContrib =
"1 5 10 0",
312 const std::string & textureFormat =
"jpg",
313 const std::map<
int, std::map<int, cv::Vec4d> > & gains = std::map<
int, std::map<int, cv::Vec4d> >(),
314 const std::map<
int, std::map<int, cv::Mat> > & blendingGains = std::map<
int, std::map<int, cv::Mat> >(),
315 const std::pair<float, float> & contrastValues = std::pair<float, float>(0,0),
317 unsigned int unwrapMethod = 0,
318 bool fillHoles =
false,
319 unsigned int padding = 5,
320 double bestScoreThreshold = 0.1,
321 double angleHardThreshold = 90.0,
322 bool forceVisibleByAllVertices =
false);
325 const cv::Mat & laserScan,
329 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
331 float searchRadius = 0.0f,
332 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
334 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
336 float searchRadius = 0.0f,
337 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
339 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
341 float searchRadius = 0.0f,
342 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
344 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
345 const pcl::IndicesPtr & indices,
347 float searchRadius = 0.0f,
348 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
350 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
351 const pcl::IndicesPtr & indices,
353 float searchRadius = 0.0f,
354 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
356 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
357 const pcl::IndicesPtr & indices,
359 float searchRadius = 0.0f,
360 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
363 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
365 float searchRadius = 0.0f,
366 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
368 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
370 float searchRadius = 0.0f,
371 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
373 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
375 float searchRadius = 0.0f,
376 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
378 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
380 float searchRadius = 0.0f,
381 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
384 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
385 float maxDepthChangeFactor = 0.02f,
386 float normalSmoothingSize = 10.0f,
387 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
389 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
390 const pcl::IndicesPtr & indices,
391 float maxDepthChangeFactor = 0.02f,
392 float normalSmoothingSize = 10.0f,
393 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
396 const LaserScan & scan,
398 cv::Mat * pcaEigenVectors = 0,
399 cv::Mat * pcaEigenValues = 0);
401 const pcl::PointCloud<pcl::Normal> & normals,
404 cv::Mat * pcaEigenVectors = 0,
405 cv::Mat * pcaEigenValues = 0);
407 const pcl::PointCloud<pcl::PointNormal> & cloud,
410 cv::Mat * pcaEigenVectors = 0,
411 cv::Mat * pcaEigenValues = 0);
413 const pcl::PointCloud<pcl::PointXYZINormal> & cloud,
416 cv::Mat * pcaEigenVectors = 0,
417 cv::Mat * pcaEigenValues = 0);
419 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
422 cv::Mat * pcaEigenVectors = 0,
423 cv::Mat * pcaEigenValues = 0);
426 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
427 float searchRadius = 0.0f,
428 int polygonialOrder = 2,
429 int upsamplingMethod = 0,
430 float upsamplingRadius = 0.0f,
431 float upsamplingStep = 0.0f,
432 int pointDensity = 0,
433 float dilationVoxelSize = 1.0f,
434 int dilationIterations = 0);
436 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
437 const pcl::IndicesPtr & indices,
438 float searchRadius = 0.0f,
439 int polygonialOrder = 2,
440 int upsamplingMethod = 0,
441 float upsamplingRadius = 0.0f,
442 float upsamplingStep = 0.0f,
443 int pointDensity = 0,
444 float dilationVoxelSize = 1.0f,
445 int dilationIterations = 0);
448 const LaserScan & scan,
449 const Eigen::Vector3f & viewpoint,
450 bool forceGroundNormalsUp),
"Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
452 const LaserScan & scan,
453 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
454 float groundNormalsUp = 0.0f);
456 pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
457 const Eigen::Vector3f & viewpoint,
458 bool forceGroundNormalsUp),
"Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
460 pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
461 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
462 float groundNormalsUp = 0.0f);
464 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
465 const Eigen::Vector3f & viewpoint,
466 bool forceGroundNormalsUp),
"Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
468 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
469 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
470 float groundNormalsUp = 0.0f);
472 pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
473 const Eigen::Vector3f & viewpoint,
474 bool forceGroundNormalsUp),
"Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
476 pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
477 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
478 float groundNormalsUp = 0.0f);
481 const std::map<int, Transform> & poses,
482 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
483 const std::vector<int> & rawCameraIndices,
484 pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
485 float groundNormalsUp = 0.0f);
487 const std::map<int, Transform> & poses,
488 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
489 const std::vector<int> & rawCameraIndices,
490 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
491 float groundNormalsUp = 0.0f);
493 const std::map<int, Transform> & poses,
494 const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
495 const std::vector<int> & rawCameraIndices,
496 pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
497 float groundNormalsUp = 0.0f);
500 const std::map<int, Transform> & viewpoints,
501 const LaserScan & rawScan,
502 const std::vector<int> & viewpointIds,
504 float groundNormalsUp = 0.0f);
508 template<
typename po
intT>
510 const pcl::PointCloud<pointT> & cloud,
511 const std::vector<pcl::Vertices> & polygons,
512 const pcl::PointXYZ & viewPoint = pcl::PointXYZ(0,0,0));
514 template<
typename po
intRGBT>
516 pcl::PolygonMeshPtr & mesh,
517 float meshDecimationFactor = 0.0f,
518 int maximumPolygons = 0,
519 const typename pcl::PointCloud<pointRGBT>::Ptr & cloud = pcl::PointCloud<pointRGBT>::Ptr(),
520 float transferColorRadius = 0.05f,
521 bool coloredOutput =
true,
522 bool cleanMesh =
true,
523 int minClusterSize = 50,
524 ProgressState * progressState = 0);
549 const Eigen::Vector3f & p,
550 const Eigen::Vector3f & dir,
551 const Eigen::Vector3f & v0,
552 const Eigen::Vector3f & v1,
553 const Eigen::Vector3f & v2,
555 Eigen::Vector3f & normal);
557 template<
typename Po
intT>
559 const Eigen::Vector3f & origin,
560 const Eigen::Vector3f & dir,
561 const typename pcl::PointCloud<PointT> & cloud,
562 const std::vector<pcl::Vertices> & polygons,
563 bool ignoreBackFaces,
565 Eigen::Vector3f & normal,
std::vector< int > RTABMAP_EXP filterNaNPointsFromMesh(const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGB > &outputCloud, std::vector< pcl::Vertices > &outputPolygons)
pcl::TextureMesh::Ptr RTABMAP_EXP concatenateTextureMeshes(const std::list< pcl::TextureMesh::Ptr > &meshes)
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_EXP computeNormals2D(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
void denseMeshPostProcessing(pcl::PolygonMeshPtr &mesh, float meshDecimationFactor, int maximumPolygons, const typename pcl::PointCloud< pointRGBT >::Ptr &cloud, float transferColorRadius, bool coloredOutput, bool cleanMesh, int minClusterSize, ProgressState *progressState)
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)
const float maxDepthError
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 intersectRayTriangle(const Eigen::Vector3f &p, const Eigen::Vector3f &dir, const Eigen::Vector3f &v0, const Eigen::Vector3f &v1, const Eigen::Vector3f &v2, float &distance, Eigen::Vector3f &normal)
GLM_FUNC_DECL genType::value_type distance(genType const &p0, genType const &p1)
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_EXP computeFastOrganizedNormals(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float maxDepthChangeFactor=0.02f, float normalSmoothingSize=10.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
RTABMAP_DEPRECATED(pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromDepth(const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0), "Use cloudFromDepth with CameraModel interface.")
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
pcl::TextureMesh::Ptr RTABMAP_EXP assembleTextureMesh(const cv::Mat &cloudMat, const std::vector< std::vector< std::vector< RTABMAP_PCL_INDEX > > > &polygons, const std::vector< std::vector< Eigen::Vector2f > > &texCoords, cv::Mat &textures, bool mergeTextures=false)
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_EXP computeFastOrganizedNormals2D(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
bool intersectRayMesh(const Eigen::Vector3f &origin, const Eigen::Vector3f &dir, const typename pcl::PointCloud< PointT > &cloud, const std::vector< pcl::Vertices > &polygons, bool ignoreBackFaces, float &distance, Eigen::Vector3f &normal, int &index)
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)
std::list< std::list< int > > RTABMAP_EXP clusterPolygons(const std::vector< std::set< int > > &neighborPolygons, int minClusterSize=0)
pcl::PolygonMesh::Ptr RTABMAP_EXP meshDecimation(const pcl::PolygonMesh::Ptr &mesh, float factor)
std::vector< pcl::Vertices > RTABMAP_EXP convertPolygonsToPCL(const std::vector< std::vector< RTABMAP_PCL_INDEX > > &polygons)
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)
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
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))
void RTABMAP_EXP concatenateTextureMaterials(pcl::TextureMesh &mesh, const cv::Size &imageSize, int textureSize, int maxTextures, float &scale, std::vector< bool > *materialsKept=0)
RecoveryProgressState state
std::vector< pcl::Vertices > normalizePolygonsSide(const typename pcl::PointCloud< pointT > &cloud, const std::vector< pcl::Vertices > &polygons, const pcl::PointXYZ &viewPoint)
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)
cv::Mat RTABMAP_EXP exposureFusion(const std::vector< cv::Mat > &images)
std::vector< std::vector< RTABMAP_PCL_INDEX > > RTABMAP_EXP convertPolygonsFromPCL(const std::vector< pcl::Vertices > &polygons)
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)
void RTABMAP_EXP fixTextureMeshForVisualization(pcl::TextureMesh &textureMesh)
std::vector< pcl::Vertices > RTABMAP_EXP filterInvalidPolygons(const std::vector< pcl::Vertices > &polygons)
void RTABMAP_EXP cleanTextureMesh(pcl::TextureMesh &textureMesh, int minClusterSize)
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...
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, float groundNormalsUp=0.0f)
float RTABMAP_EXP computeNormalsComplexity(const LaserScan &scan, const Transform &t=Transform::getIdentity(), cv::Mat *pcaEigenVectors=0, cv::Mat *pcaEigenValues=0)
pcl::PolygonMesh::Ptr RTABMAP_EXP assemblePolygonMesh(const cv::Mat &cloudMat, const std::vector< std::vector< RTABMAP_PCL_INDEX > > &polygons)
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, unsigned int textureSize=8192, unsigned int textureDownscale=2, const std::string &nbContrib="1 5 10 0", 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, unsigned int unwrapMethod=0, bool fillHoles=false, unsigned int padding=5, double bestScoreThreshold=0.1, double angleHardThreshold=90.0, bool forceVisibleByAllVertices=false)
LaserScan RTABMAP_EXP adjustNormalsToViewPoint(const LaserScan &scan, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0), float groundNormalsUp=0.0f)