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 
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 
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_EXP clusterPolygons(
71  const std::vector<std::set<int> > & neighborPolygons,
72  int minClusterSize = 0);
73 
74 std::vector<pcl::Vertices> RTABMAP_EXP 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_EXP 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_EXP 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 
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);
103 
104 // return map from new to old polygon indices
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);
115 std::vector<int> RTABMAP_EXP 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_EXP 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_EXP filterInvalidPolygons(
129  const std::vector<pcl::Vertices> & polygons);
130 
131 pcl::PolygonMesh::Ptr RTABMAP_EXP 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_EXP 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_EXP 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 
172  pcl::TextureMesh & textureMesh,
173  int minClusterSize);
174 
175 pcl::TextureMesh::Ptr RTABMAP_EXP concatenateTextureMeshes(
176  const std::list<pcl::TextureMesh::Ptr> & meshes);
177 
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_EXP convertPolygonsFromPCL(
182  const std::vector<pcl::Vertices> & polygons);
183 std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > RTABMAP_EXP convertPolygonsFromPCL(
184  const std::vector<std::vector<pcl::Vertices> > & polygons);
185 std::vector<pcl::Vertices> RTABMAP_EXP convertPolygonsToPCL(
186  const std::vector<std::vector<RTABMAP_PCL_INDEX> > & polygons);
187 std::vector<std::vector<pcl::Vertices> > RTABMAP_EXP convertPolygonsToPCL(
188  const std::vector<std::vector<std::vector<RTABMAP_PCL_INDEX> > > & tex_polygons);
189 
190 pcl::TextureMesh::Ptr RTABMAP_EXP 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_EXP assemblePolygonMesh(
202  const cv::Mat & cloudMat,
203  const std::vector<std::vector<RTABMAP_PCL_INDEX> > & polygons);
204 
209 cv::Mat RTABMAP_EXP 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_EXP 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_EXP fixTextureMeshForVisualization(pcl::TextureMesh & textureMesh);
255 
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, // required output of util3d::createTextureMesh()
262  const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
263  const std::map<int, std::vector<CameraModel> > & cameraModels, // Should match images
264  const Memory * memory = 0, // Should be set if images are not set
265  const DBDriver * dbDriver = 0, // Should be set if images and memory are not set
266  int textureSize = 8192,
267  const std::string & textureFormat = "jpg", // png, jpg
268  const std::map<int, std::map<int, cv::Vec4d> > & gains = std::map<int, std::map<int, cv::Vec4d> >(), // optional output of util3d::mergeTextures()
269  const std::map<int, std::map<int, cv::Mat> > & blendingGains = std::map<int, std::map<int, cv::Mat> >(), // optional output of util3d::mergeTextures()
270  const std::pair<float, float> & contrastValues = std::pair<float, float>(0,0), // optional output of util3d::mergeTextures()
271  bool gainRGB = true);
272 
274  const cv::Mat & laserScan,
275  int searchK,
276  float searchRadius);
277 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
278  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
279  int searchK = 20,
280  float searchRadius = 0.0f,
281  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
282 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
283  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
284  int searchK = 20,
285  float searchRadius = 0.0f,
286  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
287 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
288  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
289  int searchK = 20,
290  float searchRadius = 0.0f,
291  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
292 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
293  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
294  const pcl::IndicesPtr & indices,
295  int searchK = 20,
296  float searchRadius = 0.0f,
297  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
298 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
299  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
300  const pcl::IndicesPtr & indices,
301  int searchK = 20,
302  float searchRadius = 0.0f,
303  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
304 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
305  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
306  const pcl::IndicesPtr & indices,
307  int searchK = 20,
308  float searchRadius = 0.0f,
309  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
310 
311 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals2D(
312  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
313  int searchK = 5,
314  float searchRadius = 0.0f,
315  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
316 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals2D(
317  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
318  int searchK = 5,
319  float searchRadius = 0.0f,
320  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
321 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals2D(
322  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
323  int searchK = 5,
324  float searchRadius = 0.0f,
325  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
326 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals2D(
327  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
328  int searchK = 5,
329  float searchRadius = 0.0f,
330  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
331 
332 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals(
333  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
334  float maxDepthChangeFactor = 0.02f,
335  float normalSmoothingSize = 10.0f,
336  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
337 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals(
338  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
339  const pcl::IndicesPtr & indices,
340  float maxDepthChangeFactor = 0.02f,
341  float normalSmoothingSize = 10.0f,
342  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
343 
345  const LaserScan & scan,
346  const Transform & t = Transform::getIdentity(),
347  cv::Mat * pcaEigenVectors = 0,
348  cv::Mat * pcaEigenValues = 0);
350  const pcl::PointCloud<pcl::Normal> & normals,
351  const Transform & t = Transform::getIdentity(),
352  bool is2d = false,
353  cv::Mat * pcaEigenVectors = 0,
354  cv::Mat * pcaEigenValues = 0);
356  const pcl::PointCloud<pcl::PointNormal> & cloud,
357  const Transform & t = Transform::getIdentity(),
358  bool is2d = false,
359  cv::Mat * pcaEigenVectors = 0,
360  cv::Mat * pcaEigenValues = 0);
362  const pcl::PointCloud<pcl::PointXYZINormal> & cloud,
363  const Transform & t = Transform::getIdentity(),
364  bool is2d = false,
365  cv::Mat * pcaEigenVectors = 0,
366  cv::Mat * pcaEigenValues = 0);
368  const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
369  const Transform & t = Transform::getIdentity(),
370  bool is2d = false,
371  cv::Mat * pcaEigenVectors = 0,
372  cv::Mat * pcaEigenValues = 0);
373 
374 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
375  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
376  float searchRadius = 0.0f,
377  int polygonialOrder = 2,
378  int upsamplingMethod = 0, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
379  float upsamplingRadius = 0.0f, // SAMPLE_LOCAL_PLANE
380  float upsamplingStep = 0.0f, // SAMPLE_LOCAL_PLANE
381  int pointDensity = 0, // RANDOM_UNIFORM_DENSITY
382  float dilationVoxelSize = 1.0f, // VOXEL_GRID_DILATION
383  int dilationIterations = 0); // VOXEL_GRID_DILATION
384 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
385  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
386  const pcl::IndicesPtr & indices,
387  float searchRadius = 0.0f,
388  int polygonialOrder = 2,
389  int upsamplingMethod = 0, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
390  float upsamplingRadius = 0.0f, // SAMPLE_LOCAL_PLANE
391  float upsamplingStep = 0.0f, // SAMPLE_LOCAL_PLANE
392  int pointDensity = 0, // RANDOM_UNIFORM_DENSITY
393  float dilationVoxelSize = 1.0f, // VOXEL_GRID_DILATION
394  int dilationIterations = 0); // VOXEL_GRID_DILATION
395 
397  const LaserScan & scan,
398  const Eigen::Vector3f & viewpoint,
399  bool forceGroundNormalsUp), "Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
401  const LaserScan & scan,
402  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
403  float groundNormalsUp = 0.0f);
405  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
406  const Eigen::Vector3f & viewpoint,
407  bool forceGroundNormalsUp), "Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
409  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
410  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
411  float groundNormalsUp = 0.0f);
413  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
414  const Eigen::Vector3f & viewpoint,
415  bool forceGroundNormalsUp), "Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
417  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
418  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
419  float groundNormalsUp = 0.0f);
421  pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
422  const Eigen::Vector3f & viewpoint,
423  bool forceGroundNormalsUp), "Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp to 0.8f, otherwise set groundNormalsUp to 0.0f.");
425  pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
426  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
427  float groundNormalsUp = 0.0f);
428 
430  const std::map<int, Transform> & poses,
431  const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
432  const std::vector<int> & rawCameraIndices,
433  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
435  const std::map<int, Transform> & poses,
436  const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
437  const std::vector<int> & rawCameraIndices,
438  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
439 
440 pcl::PolygonMesh::Ptr RTABMAP_EXP meshDecimation(const pcl::PolygonMesh::Ptr & mesh, float factor);
441 
442 template<typename pointT>
443 std::vector<pcl::Vertices> normalizePolygonsSide(
444  const pcl::PointCloud<pointT> & cloud,
445  const std::vector<pcl::Vertices> & polygons,
446  const pcl::PointXYZ & viewPoint = pcl::PointXYZ(0,0,0));
447 
448 template<typename pointRGBT>
450  pcl::PolygonMeshPtr & mesh,
451  float meshDecimationFactor = 0.0f, // value between 0 and 1, 0=disabled
452  int maximumPolygons = 0, // 0=disabled
453  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)
454  float transferColorRadius = 0.05f, // <0=disabled, 0=nearest color
455  bool coloredOutput = true, // Not used anymore, output is colored if transferColorRadius>=0
456  bool cleanMesh = true, // Remove polygons not colored (if coloredOutput is disabled, transferColorRadius is still used to clean the mesh)
457  int minClusterSize = 50, // Remove small polygon clusters after the mesh has been cleaned (0=disabled)
458  ProgressState * progressState = 0);
459 
483  const Eigen::Vector3f & p,
484  const Eigen::Vector3f & dir,
485  const Eigen::Vector3f & v0,
486  const Eigen::Vector3f & v1,
487  const Eigen::Vector3f & v2,
488  float & distance,
489  Eigen::Vector3f & normal);
490 
491 template<typename PointT>
492 bool intersectRayMesh(
493  const Eigen::Vector3f & origin,
494  const Eigen::Vector3f & dir,
495  const typename pcl::PointCloud<PointT> & cloud,
496  const std::vector<pcl::Vertices> & polygons,
497  bool ignoreBackFaces,
498  float & distance,
499  Eigen::Vector3f & normal,
500  int & index);
501 
502 
503 } // namespace util3d
504 } // namespace rtabmap
505 
507 
508 #endif /* UTIL3D_SURFACE_H_ */
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
Definition: CameraTango.cpp:42
static Transform getIdentity()
Definition: Transform.cpp:380
std::vector< int > RTABMAP_EXP filterNotUsedVerticesFromMesh(const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGBNormal > &outputCloud, std::vector< pcl::Vertices > &outputPolygons)
bool RTABMAP_EXP multiBandTexturing(const std::string &outputOBJPath, const pcl::PCLPointCloud2 &cloud, const std::vector< pcl::Vertices > &polygons, const std::map< int, Transform > &cameraPoses, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels, const std::map< int, cv::Mat > &images, const std::map< int, std::vector< CameraModel > > &cameraModels, const Memory *memory=0, const DBDriver *dbDriver=0, int textureSize=8192, const std::string &textureFormat="jpg", const std::map< int, std::map< int, cv::Vec4d > > &gains=std::map< int, std::map< int, cv::Vec4d > >(), const std::map< int, std::map< int, cv::Mat > > &blendingGains=std::map< int, std::map< int, cv::Mat > >(), const std::pair< float, float > &contrastValues=std::pair< float, float >(0, 0), bool gainRGB=true)
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 detail::tmat4x4< T, P > scale(detail::tmat4x4< T, P > const &m, detail::tvec3< T, P > const &v)
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))
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)
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
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)
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.")
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)
Definition: util2d.cpp:2027
std::vector< std::vector< RTABMAP_PCL_INDEX > > RTABMAP_EXP convertPolygonsFromPCL(const std::vector< pcl::Vertices > &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)
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...
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)
LaserScan RTABMAP_EXP adjustNormalsToViewPoint(const LaserScan &scan, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0), float groundNormalsUp=0.0f)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:06