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 <set>
43 #include <list>
44 
45 namespace rtabmap
46 {
47 
48 class Memory;
49 class DBDriver;
50 
51 namespace util3d
52 {
53 
64  const std::vector<pcl::Vertices> & polygons,
65  int cloudSize,
66  std::vector<std::set<int> > & neighborPolygons,
67  std::vector<std::set<int> > & vertexPolygons);
68 
69 std::list<std::list<int> > RTABMAP_EXP clusterPolygons(
70  const std::vector<std::set<int> > & neighborPolygons,
71  int minClusterSize = 0);
72 
73 std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
74  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
75  double angleTolerance,
76  bool quad,
77  int trianglePixelSize,
78  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
79 std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
80  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
81  double angleTolerance = M_PI/16,
82  bool quad=true,
83  int trianglePixelSize = 2,
84  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
85 std::vector<pcl::Vertices> RTABMAP_EXP organizedFastMesh(
86  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
87  double angleTolerance = M_PI/16,
88  bool quad=true,
89  int trianglePixelSize = 2,
90  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
91 
93  pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudA,
94  std::vector<pcl::Vertices> & polygonsA,
95  const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloudB,
96  const std::vector<pcl::Vertices> & polygonsB);
98  pcl::PointCloud<pcl::PointXYZRGB> & cloudA,
99  std::vector<pcl::Vertices> & polygonsA,
100  const pcl::PointCloud<pcl::PointXYZRGB> & cloudB,
101  const std::vector<pcl::Vertices> & polygonsB);
102 
103 // return map from new to old polygon indices
105  const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
106  const std::vector<pcl::Vertices> & polygons,
107  pcl::PointCloud<pcl::PointXYZRGBNormal> & outputCloud,
108  std::vector<pcl::Vertices> & outputPolygons);
110  const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
111  const std::vector<pcl::Vertices> & polygons,
112  pcl::PointCloud<pcl::PointXYZRGB> & outputCloud,
113  std::vector<pcl::Vertices> & outputPolygons);
114 std::vector<int> RTABMAP_EXP filterNaNPointsFromMesh(
115  const pcl::PointCloud<pcl::PointXYZRGB> & cloud,
116  const std::vector<pcl::Vertices> & polygons,
117  pcl::PointCloud<pcl::PointXYZRGB> & outputCloud,
118  std::vector<pcl::Vertices> & outputPolygons);
119 
120 std::vector<pcl::Vertices> RTABMAP_EXP filterCloseVerticesFromMesh(
121  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud,
122  const std::vector<pcl::Vertices> & polygons,
123  float radius,
124  float angle,
125  bool keepLatestInRadius);
126 
127 std::vector<pcl::Vertices> RTABMAP_EXP filterInvalidPolygons(
128  const std::vector<pcl::Vertices> & polygons);
129 
130 pcl::PolygonMesh::Ptr RTABMAP_EXP createMesh(
131  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloudWithNormals,
132  float gp3SearchRadius = 0.025,
133  float gp3Mu = 2.5,
134  int gp3MaximumNearestNeighbors = 100,
135  float gp3MaximumSurfaceAngle = M_PI/4,
136  float gp3MinimumAngle = M_PI/18,
137  float gp3MaximumAngle = 2*M_PI/3,
138  bool gp3NormalConsistency = true);
139 
140 pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(
141  const pcl::PolygonMesh::Ptr & mesh,
142  const std::map<int, Transform> & poses,
143  const std::map<int, CameraModel> & cameraModels,
144  const std::map<int, cv::Mat> & cameraDepths,
145  float maxDistance = 0.0f, // max camera distance to polygon to apply texture
146  float maxDepthError = 0.0f, // maximum depth error between reprojected mesh and depth image to texture a face (-1=disabled, 0=edge length is used)
147  float maxAngle = 0.0f, // maximum angle between camera and face (0=disabled)
148  int minClusterSize = 50, // minimum size of polygons clusters textured
149  const std::vector<float> & roiRatios = std::vector<float>(), // [left, right, top, bottom] region of interest (in ratios) of the image projected.
150  const ProgressState * state = 0,
151  std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0);
152 pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(
153  const pcl::PolygonMesh::Ptr & mesh,
154  const std::map<int, Transform> & poses,
155  const std::map<int, std::vector<CameraModel> > & cameraModels,
156  const std::map<int, cv::Mat> & cameraDepths,
157  float maxDistance = 0.0f, // max camera distance to polygon to apply texture
158  float maxDepthError = 0.0f, // maximum depth error between reprojected mesh and depth image to texture a face (-1=disabled, 0=edge length is used)
159  float maxAngle = 0.0f, // maximum angle between camera and face (0=disabled)
160  int minClusterSize = 50, // minimum size of polygons clusters textured
161  const std::vector<float> & roiRatios = std::vector<float>(), // [left, right, top, bottom] region of interest (in ratios) of the image projected.
162  const ProgressState * state = 0,
163  std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0);
164 
169  pcl::TextureMesh & textureMesh,
170  int minClusterSize);
171 
172 pcl::TextureMesh::Ptr RTABMAP_EXP concatenateTextureMeshes(
173  const std::list<pcl::TextureMesh::Ptr> & meshes);
174 
176  pcl::TextureMesh & mesh, const cv::Size & imageSize, int textureSize, int maxTextures, float & scale, std::vector<bool> * materialsKept=0);
177 
178 std::vector<std::vector<unsigned int> > RTABMAP_EXP convertPolygonsFromPCL(
179  const std::vector<pcl::Vertices> & polygons);
180 std::vector<std::vector<std::vector<unsigned int> > > RTABMAP_EXP convertPolygonsFromPCL(
181  const std::vector<std::vector<pcl::Vertices> > & polygons);
182 std::vector<pcl::Vertices> RTABMAP_EXP convertPolygonsToPCL(
183  const std::vector<std::vector<unsigned int> > & polygons);
184 std::vector<std::vector<pcl::Vertices> > RTABMAP_EXP convertPolygonsToPCL(
185  const std::vector<std::vector<std::vector<unsigned int> > > & tex_polygons);
186 
187 pcl::TextureMesh::Ptr RTABMAP_EXP assembleTextureMesh(
188  const cv::Mat & cloudMat,
189  const std::vector<std::vector<std::vector<unsigned int> > > & polygons,
190 #if PCL_VERSION_COMPARE(>=, 1, 8, 0)
191  const std::vector<std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> > > & texCoords,
192 #else
193  const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
194 #endif
195  cv::Mat & textures,
196  bool mergeTextures = false);
197 
198 pcl::PolygonMesh::Ptr RTABMAP_EXP assemblePolygonMesh(
199  const cv::Mat & cloudMat,
200  const std::vector<std::vector<unsigned int> > & polygons);
201 
206 cv::Mat RTABMAP_EXP mergeTextures(
207  pcl::TextureMesh & mesh,
208  const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
209  const std::map<int, CameraModel> & calibrations, // Should match images
210  const Memory * memory = 0, // Should be set if images are not set
211  const DBDriver * dbDriver = 0, // Should be set if images and memory are not set
212  int textureSize = 4096,
213  int textureCount = 1,
214  const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels = std::vector<std::map<int, pcl::PointXY> >(), // needed for parameters below
215  bool gainCompensation = true,
216  float gainBeta = 10.0f,
217  bool gainRGB = true, //Do gain compensation on each channel
218  bool blending = true,
219  int blendingDecimation = 0, //0=auto depending on projected polygon size and texture size
220  int brightnessContrastRatioLow = 0, //0=disabled, values between 0 and 100
221  int brightnessContrastRatioHigh = 0, //0=disabled, values between 0 and 100
222  bool exposureFusion = false, //Exposure fusion can be used only with OpenCV3
223  const ProgressState * state = 0);
224 cv::Mat RTABMAP_EXP mergeTextures(
225  pcl::TextureMesh & mesh,
226  const std::map<int, cv::Mat> & images, // raw or compressed, can be empty if memory or dbDriver should be used
227  const std::map<int, std::vector<CameraModel> > & calibrations, // Should match images
228  const Memory * memory = 0, // Should be set if images are not set
229  const DBDriver * dbDriver = 0, // Should be set if images and memory are not set
230  int textureSize = 4096,
231  int textureCount = 1,
232  const std::vector<std::map<int, pcl::PointXY> > & vertexToPixels = std::vector<std::map<int, pcl::PointXY> >(), // needed for parameters below
233  bool gainCompensation = true,
234  float gainBeta = 10.0f,
235  bool gainRGB = true, //Do gain compensation on each channel
236  bool blending = true,
237  int blendingDecimation = 0, //0=auto depending on projected polygon size and texture size
238  int brightnessContrastRatioLow = 0, //0=disabled, values between 0 and 100
239  int brightnessContrastRatioHigh = 0, //0=disabled, values between 0 and 100
240  bool exposureFusion = false, //Exposure fusion can be used only with OpenCV3
241  const ProgressState * state = 0);
242 
243 void RTABMAP_EXP fixTextureMeshForVisualization(pcl::TextureMesh & textureMesh);
244 
246  const cv::Mat & laserScan,
247  int searchK,
248  float searchRadius);
249 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
250  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
251  int searchK = 20,
252  float searchRadius = 0.0f,
253  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
254 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
255  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
256  int searchK = 20,
257  float searchRadius = 0.0f,
258  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
259 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
260  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
261  int searchK = 20,
262  float searchRadius = 0.0f,
263  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
264 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
265  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
266  const pcl::IndicesPtr & indices,
267  int searchK = 20,
268  float searchRadius = 0.0f,
269  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
270 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
271  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
272  const pcl::IndicesPtr & indices,
273  int searchK = 20,
274  float searchRadius = 0.0f,
275  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
276 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals(
277  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
278  const pcl::IndicesPtr & indices,
279  int searchK = 20,
280  float searchRadius = 0.0f,
281  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
282 
283 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals2D(
284  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
285  int searchK = 5,
286  float searchRadius = 0.0f,
287  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
288 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeNormals2D(
289  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
290  int searchK = 5,
291  float searchRadius = 0.0f,
292  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
293 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals2D(
294  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
295  int searchK = 5,
296  float searchRadius = 0.0f,
297  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
298 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals2D(
299  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
300  int searchK = 5,
301  float searchRadius = 0.0f,
302  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
303 
304 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals(
305  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
306  float maxDepthChangeFactor = 0.02f,
307  float normalSmoothingSize = 10.0f,
308  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
309 pcl::PointCloud<pcl::Normal>::Ptr RTABMAP_EXP computeFastOrganizedNormals(
310  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
311  const pcl::IndicesPtr & indices,
312  float maxDepthChangeFactor = 0.02f,
313  float normalSmoothingSize = 10.0f,
314  const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
315 
317  const LaserScan & scan,
318  cv::Mat * pcaEigenVectors = 0,
319  cv::Mat * pcaEigenValues = 0);
321  const pcl::PointCloud<pcl::Normal> & normals,
322  bool is2d = false,
323  cv::Mat * pcaEigenVectors = 0,
324  cv::Mat * pcaEigenValues = 0);
326  const pcl::PointCloud<pcl::PointNormal> & cloud,
327  bool is2d = false,
328  cv::Mat * pcaEigenVectors = 0,
329  cv::Mat * pcaEigenValues = 0);
331  const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
332  bool is2d = false,
333  cv::Mat * pcaEigenVectors = 0,
334  cv::Mat * pcaEigenValues = 0);
335 
336 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
337  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
338  float searchRadius = 0.0f,
339  int polygonialOrder = 2,
340  int upsamplingMethod = 0, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
341  float upsamplingRadius = 0.0f, // SAMPLE_LOCAL_PLANE
342  float upsamplingStep = 0.0f, // SAMPLE_LOCAL_PLANE
343  int pointDensity = 0, // RANDOM_UNIFORM_DENSITY
344  float dilationVoxelSize = 1.0f, // VOXEL_GRID_DILATION
345  int dilationIterations = 0); // VOXEL_GRID_DILATION
346 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP mls(
347  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
348  const pcl::IndicesPtr & indices,
349  float searchRadius = 0.0f,
350  int polygonialOrder = 2,
351  int upsamplingMethod = 0, // NONE, DISTINCT_CLOUD, SAMPLE_LOCAL_PLANE, RANDOM_UNIFORM_DENSITY, VOXEL_GRID_DILATION
352  float upsamplingRadius = 0.0f, // SAMPLE_LOCAL_PLANE
353  float upsamplingStep = 0.0f, // SAMPLE_LOCAL_PLANE
354  int pointDensity = 0, // RANDOM_UNIFORM_DENSITY
355  float dilationVoxelSize = 1.0f, // VOXEL_GRID_DILATION
356  int dilationIterations = 0); // VOXEL_GRID_DILATION
357 
359  const LaserScan & scan,
360  const Eigen::Vector3f & viewpoint,
361  bool forceGroundNormalsUp);
363  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
364  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
365  bool forceGroundNormalsUp = false);
367  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
368  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0),
369  bool forceGroundNormalsUp = false);
371  const std::map<int, Transform> & poses,
372  const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
373  const std::vector<int> & rawCameraIndices,
374  pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
376  const std::map<int, Transform> & poses,
377  const pcl::PointCloud<pcl::PointXYZ>::Ptr & rawCloud,
378  const std::vector<int> & rawCameraIndices,
379  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
380 
381 pcl::PolygonMesh::Ptr RTABMAP_EXP meshDecimation(const pcl::PolygonMesh::Ptr & mesh, float factor);
382 
383 template<typename pointT>
384 std::vector<pcl::Vertices> normalizePolygonsSide(
385  const pcl::PointCloud<pointT> & cloud,
386  const std::vector<pcl::Vertices> & polygons,
387  const pcl::PointXYZ & viewPoint = pcl::PointXYZ(0,0,0));
388 
389 template<typename pointRGBT>
391  pcl::PolygonMeshPtr & mesh,
392  float meshDecimationFactor = 0.0f, // value between 0 and 1, 0=disabled
393  int maximumPolygons = 0, // 0=disabled
394  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)
395  float transferColorRadius = 0.05f, // <0=disabled, 0=nearest color
396  bool coloredOutput = true, // Not used anymore, output is colored if transferColorRadius>=0
397  bool cleanMesh = true, // Remove polygons not colored (if coloredOutput is disabled, transferColorRadius is still used to clean the mesh)
398  int minClusterSize = 50, // Remove small polygon clusters after the mesh has been cleaned (0=disabled)
399  ProgressState * progressState = 0);
400 
401 } // namespace util3d
402 } // namespace rtabmap
403 
405 
406 #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)
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)
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))
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)
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
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)
GLM_FUNC_DECL detail::tmat4x4< T, P > scale(detail::tmat4x4< T, P > const &m, detail::tvec3< T, P > const &v)
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::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))
std::vector< std::vector< unsigned int > > RTABMAP_EXP convertPolygonsFromPCL(const std::vector< pcl::Vertices > &polygons)
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::vector< pcl::Vertices > RTABMAP_EXP convertPolygonsToPCL(const std::vector< std::vector< unsigned int > > &polygons)
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)
void RTABMAP_EXP appendMesh(pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudA, std::vector< pcl::Vertices > &polygonsA, const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudB, const std::vector< pcl::Vertices > &polygonsB)
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
pcl::TextureMesh::Ptr RTABMAP_EXP assembleTextureMesh(const cv::Mat &cloudMat, const std::vector< std::vector< std::vector< unsigned int > > > &polygons, const std::vector< std::vector< Eigen::Vector2f > > &texCoords, cv::Mat &textures, bool mergeTextures=false)
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 exposureFusion(const std::vector< cv::Mat > &images)
Definition: util2d.cpp:2012
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)
void RTABMAP_EXP fixTextureMeshForVisualization(pcl::TextureMesh &textureMesh)
float RTABMAP_EXP computeNormalsComplexity(const LaserScan &scan, cv::Mat *pcaEigenVectors=0, cv::Mat *pcaEigenValues=0)
std::vector< pcl::Vertices > RTABMAP_EXP filterInvalidPolygons(const std::vector< pcl::Vertices > &polygons)
void RTABMAP_EXP cleanTextureMesh(pcl::TextureMesh &textureMesh, int minClusterSize)
LaserScan RTABMAP_EXP adjustNormalsToViewPoint(const LaserScan &scan, const Eigen::Vector3f &viewpoint, bool forceGroundNormalsUp)
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...
pcl::PolygonMesh::Ptr RTABMAP_EXP assemblePolygonMesh(const cv::Mat &cloudMat, const std::vector< std::vector< unsigned int > > &polygons)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:41