28 #ifndef UTIL3D_SURFACE_H_ 29 #define UTIL3D_SURFACE_H_ 33 #include <pcl/PolygonMesh.h> 34 #include <pcl/point_cloud.h> 35 #include <pcl/point_types.h> 36 #include <pcl/TextureMesh.h> 37 #include <pcl/pcl_base.h> 64 const std::vector<pcl::Vertices> & polygons,
66 std::vector<std::set<int> > & neighborPolygons,
67 std::vector<std::set<int> > & vertexPolygons);
70 const std::vector<std::set<int> > & neighborPolygons,
71 int minClusterSize = 0);
74 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
75 double angleTolerance,
77 int trianglePixelSize,
78 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
80 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
81 double angleTolerance =
M_PI/16,
83 int trianglePixelSize = 2,
84 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
86 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
87 double angleTolerance =
M_PI/16,
89 int trianglePixelSize = 2,
90 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
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);
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);
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);
121 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud,
122 const std::vector<pcl::Vertices> & polygons,
125 bool keepLatestInRadius);
128 const std::vector<pcl::Vertices> & polygons);
131 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloudWithNormals,
132 float gp3SearchRadius = 0.025,
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);
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,
147 float maxAngle = 0.0f,
148 int minClusterSize = 50,
149 const std::vector<float> & roiRatios = std::vector<float>(),
150 const ProgressState *
state = 0,
151 std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0);
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,
159 float maxAngle = 0.0f,
160 int minClusterSize = 50,
161 const std::vector<float> & roiRatios = std::vector<float>(),
162 const ProgressState *
state = 0,
163 std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0);
169 pcl::TextureMesh & textureMesh,
173 const std::list<pcl::TextureMesh::Ptr> & meshes);
176 pcl::TextureMesh & mesh,
const cv::Size & imageSize,
int textureSize,
int maxTextures,
float &
scale, std::vector<bool> * materialsKept=0);
179 const std::vector<pcl::Vertices> & polygons);
181 const std::vector<std::vector<pcl::Vertices> > & polygons);
183 const std::vector<std::vector<unsigned int> > & polygons);
185 const std::vector<std::vector<std::vector<unsigned int> > > & tex_polygons);
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,
193 const std::vector<std::vector<Eigen::Vector2f> > & texCoords,
199 const cv::Mat & cloudMat,
200 const std::vector<std::vector<unsigned int> > & polygons);
207 pcl::TextureMesh & mesh,
208 const std::map<int, cv::Mat> & images,
209 const std::map<int, CameraModel> & calibrations,
210 const Memory * memory = 0,
211 const DBDriver * dbDriver = 0,
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> >(),
215 bool gainCompensation =
true,
216 float gainBeta = 10.0f,
218 bool blending =
true,
219 int blendingDecimation = 0,
220 int brightnessContrastRatioLow = 0,
221 int brightnessContrastRatioHigh = 0,
223 const ProgressState *
state = 0);
225 pcl::TextureMesh & mesh,
226 const std::map<int, cv::Mat> & images,
227 const std::map<
int, std::vector<CameraModel> > & calibrations,
228 const Memory * memory = 0,
229 const DBDriver * dbDriver = 0,
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> >(),
233 bool gainCompensation =
true,
234 float gainBeta = 10.0f,
236 bool blending =
true,
237 int blendingDecimation = 0,
238 int brightnessContrastRatioLow = 0,
239 int brightnessContrastRatioHigh = 0,
241 const ProgressState *
state = 0);
246 const cv::Mat & laserScan,
250 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
252 float searchRadius = 0.0f,
253 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
255 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
257 float searchRadius = 0.0f,
258 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
260 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
262 float searchRadius = 0.0f,
263 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
265 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
266 const pcl::IndicesPtr & indices,
268 float searchRadius = 0.0f,
269 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
271 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
272 const pcl::IndicesPtr & indices,
274 float searchRadius = 0.0f,
275 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
277 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
278 const pcl::IndicesPtr & indices,
280 float searchRadius = 0.0f,
281 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
284 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
286 float searchRadius = 0.0f,
287 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
289 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
291 float searchRadius = 0.0f,
292 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
294 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
296 float searchRadius = 0.0f,
297 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
299 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
301 float searchRadius = 0.0f,
302 const Eigen::Vector3f & viewPoint = Eigen::Vector3f(0,0,0));
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));
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));
317 const LaserScan & scan,
318 cv::Mat * pcaEigenVectors = 0,
319 cv::Mat * pcaEigenValues = 0);
321 const pcl::PointCloud<pcl::Normal> & normals,
323 cv::Mat * pcaEigenVectors = 0,
324 cv::Mat * pcaEigenValues = 0);
326 const pcl::PointCloud<pcl::PointNormal> & cloud,
328 cv::Mat * pcaEigenVectors = 0,
329 cv::Mat * pcaEigenValues = 0);
331 const pcl::PointCloud<pcl::PointXYZRGBNormal> & cloud,
333 cv::Mat * pcaEigenVectors = 0,
334 cv::Mat * pcaEigenValues = 0);
337 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
338 float searchRadius = 0.0f,
339 int polygonialOrder = 2,
340 int upsamplingMethod = 0,
341 float upsamplingRadius = 0.0f,
342 float upsamplingStep = 0.0f,
343 int pointDensity = 0,
344 float dilationVoxelSize = 1.0f,
345 int dilationIterations = 0);
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,
352 float upsamplingRadius = 0.0f,
353 float upsamplingStep = 0.0f,
354 int pointDensity = 0,
355 float dilationVoxelSize = 1.0f,
356 int dilationIterations = 0);
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);
383 template<
typename po
intT>
385 const pcl::PointCloud<pointT> & cloud,
386 const std::vector<pcl::Vertices> & polygons,
387 const pcl::PointXYZ & viewPoint = pcl::PointXYZ(0,0,0));
389 template<
typename po
intRGBT>
391 pcl::PolygonMeshPtr & mesh,
392 float meshDecimationFactor = 0.0f,
393 int maximumPolygons = 0,
394 const typename pcl::PointCloud<pointRGBT>::Ptr & cloud = pcl::PointCloud<pointRGBT>::Ptr(),
395 float transferColorRadius = 0.05f,
396 bool coloredOutput =
true,
397 bool cleanMesh =
true,
398 int minClusterSize = 50,
399 ProgressState * progressState = 0);
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
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)
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)
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)
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)