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  bool clearVertexColorUnderTexture = true,
229  std::map<int, std::map<int, cv::Vec4d> > * gains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains Gray-R-G-B>
230  std::map<int, std::map<int, cv::Mat> > * blendingGains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains>
231  std::pair<float, float> * contrastValues = 0); // Alpha/beta contrast values
232 cv::Mat RTABMAP_CORE_EXPORT mergeTextures(
233  pcl::TextureMesh & mesh,
234  const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
235  const std::map<int, std::vector<CameraModel> > & calibrations, // Should match images
236  const Memory * memory = 0, // Should be set if images are not set
237  const DBDriver * dbDriver = 0, // Should be set if images and memory are not set
238  int textureSize = 4096,
239  int textureCount = 1,
240  const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels = std::vector<std::map<int, pcl::PointXY> >(), // needed for parameters below
241  bool gainCompensation = true,
242  float gainBeta = 10.0f,
243  bool gainRGB = true, //Do gain compensation on each channel
244  bool blending = true,
245  int blendingDecimation = 0, //0=auto depending on projected polygon size and texture size
246  int brightnessContrastRatioLow = 0, //0=disabled, values between 0 and 100
247  int brightnessContrastRatioHigh = 0, //0=disabled, values between 0 and 100
248  bool exposureFusion = false, //Exposure fusion can be used only with OpenCV3
249  const ProgressState * state = 0,
250  unsigned char blankValue = 255, //Gray value for blank polygons (without texture)
251  bool clearVertexColorUnderTexture = true,
252  std::map<int, std::map<int, cv::Vec4d> > * gains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains Gray-R-G-B>
253  std::map<int, std::map<int, cv::Mat> > * blendingGains = 0, // <Camera ID, Camera Sub Index (multi-cameras), gains>
254  std::pair<float, float> * contrastValues = 0); // Alpha/beta contrast values
255 
256 void RTABMAP_CORE_EXPORT fixTextureMeshForVisualization(pcl::TextureMesh & textureMesh);
257 
258 // Use the same method with 22 parameters instead.
259 RTABMAP_DEPRECATED bool RTABMAP_CORE_EXPORT multiBandTexturing(
260  const std::string & outputOBJPath,
261  const pcl::PCLPointCloud2 & cloud,
262  const std::vector<pcl::Vertices> & polygons,
263  const std::map<int, Transform> & cameraPoses,
264  const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels, // required output of util3d::createTextureMesh()
265  const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
266  const std::map<int, std::vector<CameraModel> > & cameraModels, // Should match images
267  const Memory * memory = 0, // Should be set if images are not set
268  const DBDriver * dbDriver = 0, // Should be set if images and memory are not set
269  int textureSize = 8192,
270  const std::string & textureFormat = "jpg", // png, jpg
271  const std::map<int, std::map<int, cv::Vec4d> > & gains = std::map<int, std::map<int, cv::Vec4d> >(), // optional output of util3d::mergeTextures()
272  const std::map<int, std::map<int, cv::Mat> > & blendingGains = std::map<int, std::map<int, cv::Mat> >(), // optional output of util3d::mergeTextures()
273  const std::pair<float, float> & contrastValues = std::pair<float, float>(0,0), // optional output of util3d::mergeTextures()
274  bool gainRGB = true);
275 
302 bool RTABMAP_CORE_EXPORT multiBandTexturing(
303  const std::string & outputOBJPath,
304  const pcl::PCLPointCloud2 & cloud,
305  const std::vector<pcl::Vertices> & polygons,
306  const std::map<int, Transform> & cameraPoses,
307  const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels,
308  const std::map<int, cv::Mat> & images,
309  const std::map<int, std::vector<CameraModel> > & cameraModels,
310  const Memory * memory = 0,
311  const DBDriver * dbDriver = 0,
312  unsigned int textureSize = 8192,
313  unsigned int textureDownscale = 2,
314  const std::string & nbContrib = "1 5 10 0",
315  const std::string & textureFormat = "jpg",
316  const std::map<int, std::map<int, cv::Vec4d> > & gains = std::map<int, std::map<int, cv::Vec4d> >(),
317  const std::map<int, std::map<int, cv::Mat> > & blendingGains = std::map<int, std::map<int, cv::Mat> >(),
318  const std::pair<float, float> & contrastValues = std::pair<float, float>(0,0),
319  bool gainRGB = true,
320  unsigned int unwrapMethod = 0,
321  bool fillHoles = false,
322  unsigned int padding = 5,
323  double bestScoreThreshold = 0.1,
324  double angleHardThreshold = 90.0,
325  bool forceVisibleByAllVertices = false);
326 
327 cv::Mat RTABMAP_CORE_EXPORT computeNormals(
328  const cv::Mat & laserScan,
329  int searchK,
330  float searchRadius);
331 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
332  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
333  int searchK = 20,
334  float searchRadius = 0.0f,
335  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
336 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
337  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
338  int searchK = 20,
339  float searchRadius = 0.0f,
340  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
341 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
342  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
343  int searchK = 20,
344  float searchRadius = 0.0f,
345  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
346 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
347  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
348  const pcl::IndicesPtr & indices,
349  int searchK = 20,
350  float searchRadius = 0.0f,
351  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
352 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
353  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
354  const pcl::IndicesPtr & indices,
355  int searchK = 20,
356  float searchRadius = 0.0f,
357  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
358 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals(
359  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
360  const pcl::IndicesPtr & indices,
361  int searchK = 20,
362  float searchRadius = 0.0f,
363  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
364 
365 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals2D(
366  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
367  int searchK = 5,
368  float searchRadius = 0.0f,
369  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
370 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeNormals2D(
371  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
372  int searchK = 5,
373  float searchRadius = 0.0f,
374  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
375 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals2D(
376  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
377  int searchK = 5,
378  float searchRadius = 0.0f,
379  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
380 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals2D(
381  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
382  int searchK = 5,
383  float searchRadius = 0.0f,
384  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
385 
386 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals(
387  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
388  float maxDepthChangeFactor = 0.02f,
389  float normalSmoothingSize = 10.0f,
390  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
391 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_CORE_EXPORT computeFastOrganizedNormals(
392  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
393  const pcl::IndicesPtr & indices,
394  float maxDepthChangeFactor = 0.02f,
395  float normalSmoothingSize = 10.0f,
396  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
397 
398 float RTABMAP_CORE_EXPORT computeNormalsComplexity(
399  const LaserScan & scan,
400  const Transform & t = Transform::getIdentity(),
401  cv::Mat * pcaEigenVectors = 0,
402  cv::Mat * pcaEigenValues = 0);
403 float RTABMAP_CORE_EXPORT computeNormalsComplexity(
404  const pcl::PointCloud<pcl::Normal> & normals,
405  const Transform & t = Transform::getIdentity(),
406  bool is2d = false,
407  cv::Mat * pcaEigenVectors = 0,
408  cv::Mat * pcaEigenValues = 0);
409 float RTABMAP_CORE_EXPORT computeNormalsComplexity(
410  const pcl::PointCloud<pcl::PointNormal> & cloud,
411  const Transform & t = Transform::getIdentity(),
412  bool is2d = false,
413  cv::Mat * pcaEigenVectors = 0,
414  cv::Mat * pcaEigenValues = 0);
415 float RTABMAP_CORE_EXPORT computeNormalsComplexity(
416  const pcl::PointCloud<pcl::PointXYZINormal> & cloud,
417  const Transform & t = Transform::getIdentity(),
418  bool is2d = false,
419  cv::Mat * pcaEigenVectors = 0,
420  cv::Mat * pcaEigenValues = 0);
421 float RTABMAP_CORE_EXPORT computeNormalsComplexity(
422  const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
423  const Transform & t = Transform::getIdentity(),
424  bool is2d = false,
425  cv::Mat * pcaEigenVectors = 0,
426  cv::Mat * pcaEigenValues = 0);
427 
428 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT mls(
429  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
430  float searchRadius = 0.0f,
431  int polygonialOrder = 2,
432  int upsamplingMethod = 0, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
433  float upsamplingRadius = 0.0f, // SAMPLE_LOCAL_PLANE
434  float upsamplingStep = 0.0f, // SAMPLE_LOCAL_PLANE
435  int pointDensity = 0, // RANDOM_UNIFORM_DENSITY
436  float dilationVoxelSize = 1.0f, // VOXEL_GRID_DILATION
437  int dilationIterations = 0); // VOXEL_GRID_DILATION
438 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT mls(
439  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
440  const pcl::IndicesPtr & indices,
441  float searchRadius = 0.0f,
442  int polygonialOrder = 2,
443  int upsamplingMethod = 0, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
444  float upsamplingRadius = 0.0f, // SAMPLE_LOCAL_PLANE
445  float upsamplingStep = 0.0f, // SAMPLE_LOCAL_PLANE
446  int pointDensity = 0, // RANDOM_UNIFORM_DENSITY
447  float dilationVoxelSize = 1.0f, // VOXEL_GRID_DILATION
448  int dilationIterations = 0); // VOXEL_GRID_DILATION
449 
450 // Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
451 RTABMAP_DEPRECATED LaserScan RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
452  const LaserScan & scan,
453  const Eigen::Vector3f & viewpoint,
454  bool forceGroundNormalsUp);
455 LaserScan RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
456  const LaserScan & scan,
457  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
458  float groundNormalsUp = 0.0f);
459 // Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
460 RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
461  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
462  const Eigen::Vector3f & viewpoint,
463  bool forceGroundNormalsUp);
464 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
465  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
466  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
467  float groundNormalsUp = 0.0f);
468 // Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
469 RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
470  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
471  const Eigen::Vector3f & viewpoint,
472  bool forceGroundNormalsUp);
473 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
474  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
475  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
476  float groundNormalsUp = 0.0f);
477 // Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.
478 RTABMAP_DEPRECATED void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
479  pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
480  const Eigen::Vector3f & viewpoint,
481  bool forceGroundNormalsUp);
482 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoint(
483  pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
484  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
485  float groundNormalsUp = 0.0f);
486 
487 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
488  const std::map<int, Transform> & poses,
489  const std::vector<int> & cameraIndices,
490  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
491  float groundNormalsUp = 0.0f);
492 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
493  const std::map<int, Transform> & poses,
494  const std::vector<int> & cameraIndices,
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 std::vector<int> & cameraIndices,
500  pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
501  float groundNormalsUp = 0.0f);
502 
503 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
504  const std::map<int, Transform> & poses,
505  const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
506  const std::vector<int> & rawCameraIndices,
507  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
508  float groundNormalsUp = 0.0f);
509 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
510  const std::map<int, Transform> & poses,
511  const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
512  const std::vector<int> & rawCameraIndices,
513  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
514  float groundNormalsUp = 0.0f);
515 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
516  const std::map<int, Transform> & poses,
517  const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
518  const std::vector<int> & rawCameraIndices,
519  pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
520  float groundNormalsUp = 0.0f);
521 
522 void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(
523  const std::map<int, Transform> & viewpoints,
524  const LaserScan & rawScan,
525  const std::vector<int> & viewpointIds,
526  LaserScan & scan,
527  float groundNormalsUp = 0.0f);
528 
529 pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT meshDecimation(const pcl::PolygonMesh::Ptr & mesh, float factor);
530 
531 template<typename pointT>
532 std::vector<pcl::Vertices> normalizePolygonsSide(
533  const pcl::PointCloud<pointT> & cloud,
534  const std::vector<pcl::Vertices> & polygons,
535  const pcl::PointXYZ & viewPoint = pcl::PointXYZ(0,0,0));
536 
537 template<typename pointRGBT>
539  pcl::PolygonMeshPtr & mesh,
540  float meshDecimationFactor = 0.0f, // value between 0 and 1, 0=disabled
541  int maximumPolygons = 0, // 0=disabled
542  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)
543  float transferColorRadius = 0.05f, // <0=disabled, 0=nearest color
544  bool coloredOutput = true, // Not used anymore, output is colored if transferColorRadius>=0
545  bool cleanMesh = true, // Remove polygons not colored (if coloredOutput is disabled, transferColorRadius is still used to clean the mesh)
546  int minClusterSize = 50, // Remove small polygon clusters after the mesh has been cleaned (0=disabled)
547  ProgressState * progressState = 0);
548 
571 bool RTABMAP_CORE_EXPORT intersectRayTriangle(
572  const Eigen::Vector3f & p,
573  const Eigen::Vector3f & dir,
574  const Eigen::Vector3f & v0,
575  const Eigen::Vector3f & v1,
576  const Eigen::Vector3f & v2,
577  float & distance,
578  Eigen::Vector3f & normal);
579 
580 template<typename PointT>
581 bool intersectRayMesh(
582  const Eigen::Vector3f & origin,
583  const Eigen::Vector3f & dir,
584  const typename pcl::PointCloud<PointT> & cloud,
585  const std::vector<pcl::Vertices> & polygons,
586  bool ignoreBackFaces,
587  float & distance,
588  Eigen::Vector3f & normal,
589  int & index);
590 
591 int RTABMAP_CORE_EXPORT saveOBJFile(
592  const std::string &file_name,
593  const pcl::TextureMesh &tex_mesh,
594  unsigned precision = 5);
595 
596 int RTABMAP_CORE_EXPORT saveOBJFile(
597  const std::string &file_name,
598  const pcl::PolygonMesh &mesh,
599  unsigned precision = 5);
600 
601 } // namespace util3d
602 } // namespace rtabmap
603 
605 
606 #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:315
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:3569
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:3904
rtabmap::util3d::adjustNormalsToViewPoints
void RTABMAP_CORE_EXPORT adjustNormalsToViewPoints(const std::map< int, Transform > &poses, const std::vector< int > &cameraIndices, pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, float groundNormalsUp=0.0f)
Definition: util3d_surface.cpp:3730
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:3167
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:3119
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::saveOBJFile
int RTABMAP_CORE_EXPORT saveOBJFile(const std::string &file_name, const pcl::TextureMesh &tex_mesh, unsigned precision=5)
Definition: util3d_surface.cpp:3955
rtabmap::util3d::meshDecimation
pcl::PolygonMesh::Ptr RTABMAP_CORE_EXPORT meshDecimation(const pcl::PolygonMesh::Ptr &mesh, float factor)
Definition: util3d_surface.cpp:3889
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:2990
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:2301
glm::precision
precision
Definition: precision.hpp:33
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::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:3470
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::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, bool clearVertexColorUnderTexture=true, 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
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:2262
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:3102
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 Mon Apr 28 2025 02:46:07