util3d_surface.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef UTIL3D_SURFACE_H_
29 #define UTIL3D_SURFACE_H_
30 
31 #include <rtabmap/core/rtabmap_core_export.h>
32 
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>
38 #include <rtabmap/core/Transform.h>
41 #include <rtabmap/core/LaserScan.h>
42 #include <rtabmap/core/Version.h>
43 #include <set>
44 #include <list>
45 
46 namespace rtabmap
47 {
48 
49 class Memory;
50 class DBDriver;
51 
52 namespace util3d
53 {
54 
64 void RTABMAP_CORE_EXPORT createPolygonIndexes(
65  const std::vector<pcl::Vertices> & polygons,
66  int cloudSize,
67  std::vector<std::set<int> > & neighborPolygons,
68  std::vector<std::set<int> > & vertexPolygons);
69 
70 std::list<std::list<int> > RTABMAP_CORE_EXPORT clusterPolygons(
71  const std::vector<std::set<int> > & neighborPolygons,
72  int minClusterSize = 0);
73 
74 std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT organizedFastMesh(
75  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
76  double angleTolerance,
77  bool quad,
78  int trianglePixelSize,
79  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
80 std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT organizedFastMesh(
81  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
82  double angleTolerance = M_PI/16,
83  bool quad=true,
84  int trianglePixelSize = 2,
85  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
86 std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT organizedFastMesh(
87  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
88  double angleTolerance = M_PI/16,
89  bool quad=true,
90  int trianglePixelSize = 2,
91  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
92 
93 void RTABMAP_CORE_EXPORT appendMesh(
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);
98 void RTABMAP_CORE_EXPORT appendMesh(
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);
103 
104 // return map from new to old polygon indices
105 std::vector<int> RTABMAP_CORE_EXPORT filterNotUsedVerticesFromMesh(
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);
110 std::vector<int> RTABMAP_CORE_EXPORT filterNotUsedVerticesFromMesh(
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);
115 std::vector<int> RTABMAP_CORE_EXPORT filterNaNPointsFromMesh(
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);
120 
121 std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT filterCloseVerticesFromMesh(
122  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud,
123  const std::vector<pcl::Vertices> & polygons,
124  float radius,
125  float angle,
126  bool keepLatestInRadius);
127 
128 std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT filterInvalidPolygons(
129  const std::vector<pcl::Vertices> & polygons);
130 
131 pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT createMesh(
132  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloudWithNormals,
133  float gp3SearchRadius = 0.025,
134  float gp3Mu = 2.5,
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);
140 
141 pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT createTextureMesh(
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, // max camera distance to polygon to apply texture
147  float maxDepthError = 0.0f, // maximum depth error between reprojected mesh and depth image to texture a face (-1=disabled, 0=edge length is used)
148  float maxAngle = 0.0f, // maximum angle between camera and face (0=disabled)
149  int minClusterSize = 50, // minimum size of polygons clusters textured
150  const std::vector<float> & roiRatios = std::vector<float>(), // [left, right, top, bottom] region of interest (in ratios) of the image projected.
151  const ProgressState * state = 0,
152  std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0, // For each point, we have a list of cameras with corresponding pixel in it. Beware that the camera ids don't correspond to pose ids, they are indexes from 0 to total camera models and texture's materials.
153  bool distanceToCamPolicy = false);
154 pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT createTextureMesh(
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, // max camera distance to polygon to apply texture
160  float maxDepthError = 0.0f, // maximum depth error between reprojected mesh and depth image to texture a face (-1=disabled, 0=edge length is used)
161  float maxAngle = 0.0f, // maximum angle between camera and face (0=disabled)
162  int minClusterSize = 50, // minimum size of polygons clusters textured
163  const std::vector<float> & roiRatios = std::vector<float>(), // [left, right, top, bottom] region of interest (in ratios) of the image projected.
164  const ProgressState * state = 0,
165  std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0, // For each point, we have a list of cameras with corresponding pixel in it. Beware that the camera ids don't correspond to pose ids, they are indexes from 0 to total camera models and texture's materials.
166  bool distanceToCamPolicy = false);
167 
171 void RTABMAP_CORE_EXPORT cleanTextureMesh(
172  pcl::TextureMesh & textureMesh,
173  int minClusterSize);
174 
175 pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT concatenateTextureMeshes(
176  const std::list<pcl::TextureMesh::Ptr> & meshes);
177 
178 void RTABMAP_CORE_EXPORT concatenateTextureMaterials(
179  pcl::TextureMesh & mesh, const cv::Size & imageSize, int textureSize, int maxTextures, float & scale, std::vector<bool> * materialsKept=0);
180 
181 std::vector<std::vector<RTABMAP_PCL_INDEX> > RTABMAP_CORE_EXPORT convertPolygonsFromPCL(
182  const std::vector<pcl::Vertices> & polygons);
183 std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > RTABMAP_CORE_EXPORT convertPolygonsFromPCL(
184  const std::vector<std::vector<pcl::Vertices> > & polygons);
185 std::vector<pcl::Vertices> RTABMAP_CORE_EXPORT convertPolygonsToPCL(
186  const std::vector<std::vector<RTABMAP_PCL_INDEX> > & polygons);
187 std::vector<std::vector<pcl::Vertices> > RTABMAP_CORE_EXPORT convertPolygonsToPCL(
188  const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & tex_polygons);
189 
190 pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT assembleTextureMesh(
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,
195 #else
196  const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
197 #endif
198  cv::Mat & textures,
199  bool mergeTextures = false);
200 
201 pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT assemblePolygonMesh(
202  const cv::Mat & cloudMat,
203  const std::vector<std::vector<RTABMAP_PCL_INDEX> > & polygons);
204 
209 cv::Mat RTABMAP_CORE_EXPORT mergeTextures(
210  pcl::TextureMesh & mesh,
211  const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
212  const std::map<int, CameraModel> & calibrations, // Should match images
213  const Memory * memory = 0, // Should be set if images are not set
214  const DBDriver * dbDriver = 0, // Should be set if images and memory are not set
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> >(), // needed for parameters below
218  bool gainCompensation = true,
219  float gainBeta = 10.0f,
220  bool gainRGB = true, //Do gain compensation on each channel
221  bool blending = true,
222  int blendingDecimation = 0, //0=auto depending on projected polygon size and texture size
223  int brightnessContrastRatioLow = 0, //0=disabled, values between 0 and 100
224  int brightnessContrastRatioHigh = 0, //0=disabled, values between 0 and 100
225  bool exposureFusion = false, //Exposure fusion can be used only with OpenCV3
226  const ProgressState * state = 0,
227  unsigned char blankValue = 255, //Gray value for blank polygons (without texture)
228  std::map<int, std::map<int, cv::Vec4d> > * gains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains Gray-R-G-B>
229  std::map<int, std::map<int, cv::Mat> > * blendingGains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains>
230  std::pair<float, float> * contrastValues = 0); // Alpha/beta contrast values
231 cv::Mat RTABMAP_CORE_EXPORT mergeTextures(
232  pcl::TextureMesh & mesh,
233  const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
234  const std::map<int, std::vector<CameraModel> > & calibrations, // Should match images
235  const Memory * memory = 0, // Should be set if images are not set
236  const DBDriver * dbDriver = 0, // Should be set if images and memory are not set
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> >(), // needed for parameters below
240  bool gainCompensation = true,
241  float gainBeta = 10.0f,
242  bool gainRGB = true, //Do gain compensation on each channel
243  bool blending = true,
244  int blendingDecimation = 0, //0=auto depending on projected polygon size and texture size
245  int brightnessContrastRatioLow = 0, //0=disabled, values between 0 and 100
246  int brightnessContrastRatioHigh = 0, //0=disabled, values between 0 and 100
247  bool exposureFusion = false, //Exposure fusion can be used only with OpenCV3
248  const ProgressState * state = 0,
249  unsigned char blankValue = 255, //Gray value for blank polygons (without texture)
250  std::map<int, std::map<int, cv::Vec4d> > * gains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains Gray-R-G-B>
251  std::map<int, std::map<int, cv::Mat> > * blendingGains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains>
252  std::pair<float, float> * contrastValues = 0); // Alpha/beta contrast values
253 
254 void RTABMAP_CORE_EXPORT fixTextureMeshForVisualization(pcl::TextureMesh & textureMesh);
255 
256 // Use the same method with 22 parameters instead.
257 RTABMAP_DEPRECATED bool RTABMAP_CORE_EXPORT multiBandTexturing(
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, // required output of util3d::createTextureMesh()
263  const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
264  const std::map<int, std::vector<CameraModel> > & cameraModels, // Should match images
265  const Memory * memory = 0, // Should be set if images are not set
266  const DBDriver * dbDriver = 0, // Should be set if images and memory are not set
267  int textureSize = 8192,
268  const std::string & textureFormat = "jpg", // png, jpg
269  const std::map<int, std::map<int, cv::Vec4d> > & gains = std::map<int, std::map<int, cv::Vec4d> >(), // optional output of util3d::mergeTextures()
270  const std::map<int, std::map<int, cv::Mat> > & blendingGains = std::map<int, std::map<int, cv::Mat> >(), // optional output of util3d::mergeTextures()
271  const std::pair<float, float> & contrastValues = std::pair<float, float>(0,0), // optional output of util3d::mergeTextures()
272  bool gainRGB = true);
273 
300 bool RTABMAP_CORE_EXPORT multiBandTexturing(
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),
317  bool gainRGB = true,
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);
324 
325 cv::Mat RTABMAP_CORE_EXPORT computeNormals(
326  const cv::Mat & laserScan,
327  int searchK,
328  float searchRadius);
329 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
330  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
331  int searchK = 20,
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,
336  int searchK = 20,
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,
341  int searchK = 20,
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,
347  int searchK = 20,
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,
353  int searchK = 20,
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,
359  int searchK = 20,
360  float searchRadius = 0.0f,
361  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
362 
363 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals2D(
364  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
365  int searchK = 5,
366  float searchRadius = 0.0f,
367  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
368 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals2D(
369  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
370  int searchK = 5,
371  float searchRadius = 0.0f,
372  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
373 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals2D(
374  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
375  int searchK = 5,
376  float searchRadius = 0.0f,
377  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
378 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals2D(
379  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
380  int searchK = 5,
381  float searchRadius = 0.0f,
382  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
383 
384 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals(
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));
389 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals(
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));
395 
396 float RTABMAP_CORE_EXPORT computeNormalsComplexity(
397  const LaserScan & scan,
398  const Transform & t = Transform::getIdentity(),
399  cv::Mat * pcaEigenVectors = 0,
400  cv::Mat * pcaEigenValues = 0);
401 float RTABMAP_CORE_EXPORT computeNormalsComplexity(
402  const pcl::PointCloud<pcl::Normal> & normals,
403  const Transform & t = Transform::getIdentity(),
404  bool is2d = false,
405  cv::Mat * pcaEigenVectors = 0,
406  cv::Mat * pcaEigenValues = 0);
407 float RTABMAP_CORE_EXPORT computeNormalsComplexity(
408  const pcl::PointCloud<pcl::PointNormal> & cloud,
409  const Transform & t = Transform::getIdentity(),
410  bool is2d = false,
411  cv::Mat * pcaEigenVectors = 0,
412  cv::Mat * pcaEigenValues = 0);
413 float RTABMAP_CORE_EXPORT computeNormalsComplexity(
414  const pcl::PointCloud<pcl::PointXYZINormal> & cloud,
415  const Transform & t = Transform::getIdentity(),
416  bool is2d = false,
417  cv::Mat * pcaEigenVectors = 0,
418  cv::Mat * pcaEigenValues = 0);
419 float RTABMAP_CORE_EXPORT computeNormalsComplexity(
420  const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
421  const Transform & t = Transform::getIdentity(),
422  bool is2d = false,
423  cv::Mat * pcaEigenVectors = 0,
424  cv::Mat * pcaEigenValues = 0);
425 
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, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
431  float upsamplingRadius = 0.0f, // SAMPLE_LOCAL_PLANE
432  float upsamplingStep = 0.0f, // SAMPLE_LOCAL_PLANE
433  int pointDensity = 0, // RANDOM_UNIFORM_DENSITY
434  float dilationVoxelSize = 1.0f, // VOXEL_GRID_DILATION
435  int dilationIterations = 0); // VOXEL_GRID_DILATION
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, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
442  float upsamplingRadius = 0.0f, // SAMPLE_LOCAL_PLANE
443  float upsamplingStep = 0.0f, // SAMPLE_LOCAL_PLANE
444  int pointDensity = 0, // RANDOM_UNIFORM_DENSITY
445  float dilationVoxelSize = 1.0f, // VOXEL_GRID_DILATION
446  int dilationIterations = 0); // VOXEL_GRID_DILATION
447 
448 // Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
449 RTABMAP_DEPRECATED LaserScan RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
450  const LaserScan & scan,
451  const Eigen::Vector3f & viewpoint,
452  bool forceGroundNormalsUp);
453 LaserScan RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
454  const LaserScan & scan,
455  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
456  float groundNormalsUp = 0.0f);
457 // Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
458 RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
459  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
460  const Eigen::Vector3f & viewpoint,
461  bool forceGroundNormalsUp);
462 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
463  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
464  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
465  float groundNormalsUp = 0.0f);
466 // Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
467 RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
468  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
469  const Eigen::Vector3f & viewpoint,
470  bool forceGroundNormalsUp);
471 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
472  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
473  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
474  float groundNormalsUp = 0.0f);
475 // Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
476 RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
477  pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
478  const Eigen::Vector3f & viewpoint,
479  bool forceGroundNormalsUp);
480 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
481  pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
482  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
483  float groundNormalsUp = 0.0f);
484 
485 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
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);
491 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
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);
497 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
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);
503 
504 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
505  const std::map<int, Transform> & viewpoints,
506  const LaserScan & rawScan,
507  const std::vector<int> & viewpointIds,
508  LaserScan & scan,
509  float groundNormalsUp = 0.0f);
510 
511 pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT meshDecimation(const pcl::PolygonMesh::Ptr & mesh, float factor);
512 
513 template<typename pointT>
514 std::vector<pcl::Vertices> normalizePolygonsSide(
515  const pcl::PointCloud<pointT> & cloud,
516  const std::vector<pcl::Vertices> & polygons,
517  const pcl::PointXYZ & viewPoint = pcl::PointXYZ(0,0,0));
518 
519 template<typename pointRGBT>
521  pcl::PolygonMeshPtr & mesh,
522  float meshDecimationFactor = 0.0f, // value between 0 and 1, 0=disabled
523  int maximumPolygons = 0, // 0=disabled
524  const typename pcl::PointCloud<pointRGBT>::Ptr & cloud = pcl::PointCloud<pointRGBT>::Ptr(), // A RGB point cloud used to transfer colors back to mesh (needed for parameters below)
525  float transferColorRadius = 0.05f, // <0=disabled, 0=nearest color
526  bool coloredOutput = true, // Not used anymore, output is colored if transferColorRadius>=0
527  bool cleanMesh = true, // Remove polygons not colored (if coloredOutput is disabled, transferColorRadius is still used to clean the mesh)
528  int minClusterSize = 50, // Remove small polygon clusters after the mesh has been cleaned (0=disabled)
529  ProgressState * progressState = 0);
530 
553 bool RTABMAP_CORE_EXPORT intersectRayTriangle(
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,
559  float & distance,
560  Eigen::Vector3f & normal);
561 
562 template<typename PointT>
563 bool intersectRayMesh(
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,
569  float & distance,
570  Eigen::Vector3f & normal,
571  int & index);
572 
573 
574 } // namespace util3d
575 } // namespace rtabmap
576 
578 
579 #endif /* UTIL3D_SURFACE_H_ */
rtabmap::util3d::createPolygonIndexes
void RTABMAP_CORE_EXPORT createPolygonIndexes(const std::vector< pcl::Vertices > &polygons, int cloudSize, std::vector< std::set< int > > &neighborPolygons, std::vector< std::set< int > > &vertexPolygons)
Given a set of polygons, create two indexes: polygons to neighbor polygons and vertices to polygons.
Definition: util3d_surface.cpp:94
rtabmap::util3d::intersectRayMesh
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)
Definition: util3d_surface.hpp:322
rtabmap::util3d::filterInvalidPolygons
std::vector< pcl::Vertices > RTABMAP_CORE_EXPORT filterInvalidPolygons(const std::vector< pcl::Vertices > &polygons)
Definition: util3d_surface.cpp:531
rtabmap::util3d::cleanTextureMesh
void RTABMAP_CORE_EXPORT cleanTextureMesh(pcl::TextureMesh &textureMesh, int minClusterSize)
Definition: util3d_surface.cpp:873
rtabmap::util3d::normalizePolygonsSide
std::vector< pcl::Vertices > normalizePolygonsSide(const typename pcl::PointCloud< pointT > &cloud, const std::vector< pcl::Vertices > &polygons, const pcl::PointXYZ &viewPoint)
Definition: util3d_surface.hpp:20
rtabmap::Transform::getIdentity
static Transform getIdentity()
Definition: Transform.cpp:411
rtabmap::util3d::createTextureMesh
pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT createTextureMesh(const pcl::PolygonMesh::Ptr &mesh, const std::map< int, Transform > &poses, const std::map< int, CameraModel > &cameraModels, const std::map< int, cv::Mat > &cameraDepths, float maxDistance=0.0f, float maxDepthError=0.0f, float maxAngle=0.0f, int minClusterSize=50, const std::vector< float > &roiRatios=std::vector< float >(), const ProgressState *state=0, std::vector< std::map< int, pcl::PointXY > > *vertexToPixels=0, bool distanceToCamPolicy=false)
Definition: util3d_surface.cpp:675
rtabmap::util3d::appendMesh
void RTABMAP_CORE_EXPORT appendMesh(pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudA, std::vector< pcl::Vertices > &polygonsA, const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudB, const std::vector< pcl::Vertices > &polygonsB)
Definition: util3d_surface.cpp:283
rtabmap::RTABMAP_DEPRECATED
RTABMAP_DEPRECATED(typedef SensorData Image, "rtabmap::Image class is renamed to rtabmap::SensorData, use the last one instead.")
Transform.h
state
RecoveryProgressState state
Definition: tools/Recovery/main.cpp:56
rtabmap::util3d::assembleTextureMesh
pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT 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)
Definition: util3d_surface.cpp:1272
rtabmap::util3d::clusterPolygons
std::list< std::list< int > > RTABMAP_CORE_EXPORT clusterPolygons(const std::vector< std::set< int > > &neighborPolygons, int minClusterSize=0)
Definition: util3d_surface.cpp:131
rtabmap::util3d::adjustNormalsToViewPoint
RTABMAP_DEPRECATED LaserScan RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(const LaserScan &scan, const Eigen::Vector3f &viewpoint, bool forceGroundNormalsUp)
Definition: util3d_surface.cpp:3502
ProgressState.h
rtabmap::util3d::convertPolygonsFromPCL
std::vector< std::vector< RTABMAP_PCL_INDEX > > RTABMAP_CORE_EXPORT convertPolygonsFromPCL(const std::vector< pcl::Vertices > &polygons)
Definition: util3d_surface.cpp:1227
rtabmap::util3d::denseMeshPostProcessing
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)
Definition: util3d_surface.hpp:50
rtabmap::maxDepthError
const float maxDepthError
Definition: CameraTango.cpp:43
rtabmap::util3d::organizedFastMesh
std::vector< pcl::Vertices > RTABMAP_CORE_EXPORT organizedFastMesh(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, double angleTolerance, bool quad, int trianglePixelSize, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0))
Definition: util3d_surface.cpp:168
rtabmap::util3d::intersectRayTriangle
bool RTABMAP_CORE_EXPORT 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)
Definition: util3d_surface.cpp:3776
rtabmap::util3d::computeNormalsComplexity
float RTABMAP_CORE_EXPORT computeNormalsComplexity(const LaserScan &scan, const Transform &t=Transform::getIdentity(), cv::Mat *pcaEigenVectors=0, cv::Mat *pcaEigenValues=0)
Definition: util3d_surface.cpp:3100
rtabmap::util3d::mergeTextures
cv::Mat RTABMAP_CORE_EXPORT mergeTextures(pcl::TextureMesh &mesh, const std::map< int, cv::Mat > &images, const std::map< int, CameraModel > &calibrations, const Memory *memory=0, const DBDriver *dbDriver=0, int textureSize=4096, int textureCount=1, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels=std::vector< std::map< int, pcl::PointXY > >(), bool gainCompensation=true, float gainBeta=10.0f, bool gainRGB=true, bool blending=true, int blendingDecimation=0, int brightnessContrastRatioLow=0, int brightnessContrastRatioHigh=0, bool exposureFusion=false, const ProgressState *state=0, unsigned char blankValue=255, std::map< int, std::map< int, cv::Vec4d > > *gains=0, std::map< int, std::map< int, cv::Mat > > *blendingGains=0, std::pair< float, float > *contrastValues=0)
Definition: util3d_surface.cpp:1438
Eigen::aligned_allocator
rtabmap::util3d::computeFastOrganizedNormals
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT 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))
Definition: util3d_surface.cpp:3052
rtabmap::util3d::concatenateTextureMaterials
void RTABMAP_CORE_EXPORT concatenateTextureMaterials(pcl::TextureMesh &mesh, const cv::Size &imageSize, int textureSize, int maxTextures, float &scale, std::vector< bool > *materialsKept=0)
Definition: util3d_surface.cpp:1079
rtabmap::util3d::filterNotUsedVerticesFromMesh
std::vector< int > RTABMAP_CORE_EXPORT filterNotUsedVerticesFromMesh(const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGBNormal > &outputCloud, std::vector< pcl::Vertices > &outputPolygons)
Definition: util3d_surface.cpp:335
glm::angle
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
rtabmap::util3d::meshDecimation
pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT meshDecimation(const pcl::PolygonMesh::Ptr &mesh, float factor)
Definition: util3d_surface.cpp:3761
rtabmap::util3d::computeNormals2D
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT computeNormals2D(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
Definition: util3d_surface.cpp:2923
rtabmap::util3d::multiBandTexturing
RTABMAP_DEPRECATED bool RTABMAP_CORE_EXPORT multiBandTexturing(const std::string &outputOBJPath, const pcl::PCLPointCloud2 &cloud, const std::vector< pcl::Vertices > &polygons, const std::map< int, Transform > &cameraPoses, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels, const std::map< int, cv::Mat > &images, const std::map< int, std::vector< CameraModel > > &cameraModels, const Memory *memory=0, const DBDriver *dbDriver=0, int textureSize=8192, const std::string &textureFormat="jpg", const std::map< int, std::map< int, cv::Vec4d > > &gains=std::map< int, std::map< int, cv::Vec4d > >(), const std::map< int, std::map< int, cv::Mat > > &blendingGains=std::map< int, std::map< int, cv::Mat > >(), const std::pair< float, float > &contrastValues=std::pair< float, float >(0, 0), bool gainRGB=true)
Definition: util3d_surface.cpp:2234
rtabmap::util3d::filterNaNPointsFromMesh
std::vector< int > RTABMAP_CORE_EXPORT filterNaNPointsFromMesh(const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGB > &outputCloud, std::vector< pcl::Vertices > &outputPolygons)
Definition: util3d_surface.cpp:415
util3d_surface.hpp
M_PI
#define M_PI
Definition: tango-gl/include/tango-gl/util.h:66
rtabmap::util3d::adjustNormalsToViewPoints
void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(const std::map< int, Transform > &poses, const pcl::PointCloud< pcl::PointXYZ >::Ptr &rawCloud, const std::vector< int > &rawCameraIndices, pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, float groundNormalsUp=0.0f)
Definition: util3d_surface.cpp:3679
rtabmap::util3d::mls
pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr RTABMAP_CORE_EXPORT mls(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float searchRadius=0.0f, int polygonialOrder=2, int upsamplingMethod=0, float upsamplingRadius=0.0f, float upsamplingStep=0.0f, int pointDensity=0, float dilationVoxelSize=1.0f, int dilationIterations=0)
Definition: util3d_surface.cpp:3403
rtabmap::util3d::createMesh
pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT createMesh(const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloudWithNormals, float gp3SearchRadius=0.025, float gp3Mu=2.5, int gp3MaximumNearestNeighbors=100, float gp3MaximumSurfaceAngle=M_PI/4, float gp3MinimumAngle=M_PI/18, float gp3MaximumAngle=2 *M_PI/3, bool gp3NormalConsistency=true)
Definition: util3d_surface.cpp:555
rtabmap::util3d::assemblePolygonMesh
pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT assemblePolygonMesh(const cv::Mat &cloudMat, const std::vector< std::vector< RTABMAP_PCL_INDEX > > &polygons)
Definition: util3d_surface.cpp:1395
LaserScan.h
rtabmap::util3d::concatenateTextureMeshes
pcl::TextureMesh::Ptr RTABMAP_CORE_EXPORT concatenateTextureMeshes(const std::list< pcl::TextureMesh::Ptr > &meshes)
Definition: util3d_surface.cpp:1006
CameraModel.h
rtabmap::util2d::exposureFusion
cv::Mat RTABMAP_CORE_EXPORT exposureFusion(const std::vector< cv::Mat > &images)
Definition: util2d.cpp:2027
rtabmap::util3d::computeNormals
cv::Mat RTABMAP_CORE_EXPORT computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
rtabmap::util3d::convertPolygonsToPCL
std::vector< pcl::Vertices > RTABMAP_CORE_EXPORT convertPolygonsToPCL(const std::vector< std::vector< RTABMAP_PCL_INDEX > > &polygons)
Definition: util3d_surface.cpp:1249
rtabmap::util3d::fixTextureMeshForVisualization
void RTABMAP_CORE_EXPORT fixTextureMeshForVisualization(pcl::TextureMesh &textureMesh)
Definition: util3d_surface.cpp:2195
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::util3d::computeFastOrganizedNormals2D
pcl::PointCloud< pcl::Normal >::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals2D(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int searchK=5, float searchRadius=0.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
Definition: util3d_surface.cpp:3035
rtabmap::util3d::filterCloseVerticesFromMesh
std::vector< pcl::Vertices > RTABMAP_CORE_EXPORT filterCloseVerticesFromMesh(const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr cloud, const std::vector< pcl::Vertices > &polygons, float radius, float angle, bool keepLatestInRadius)
Definition: util3d_surface.cpp:458


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:24