Namespaces | Functions
util3d_surface.h File Reference
#include <rtabmap/core/RtabmapExp.h>
#include <pcl/PolygonMesh.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/TextureMesh.h>
#include <pcl/pcl_base.h>
#include <rtabmap/core/Transform.h>
#include <rtabmap/core/CameraModel.h>
#include <set>
Include dependency graph for util3d_surface.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  rtabmap
namespace  rtabmap::util3d

Functions

void RTABMAP_EXP rtabmap::util3d::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 rtabmap::util3d::adjustNormalsToViewPoints (const std::map< int, Transform > &poses, const pcl::PointCloud< pcl::PointXYZ >::Ptr &rawCloud, const std::vector< int > &rawCameraIndices, pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud)
void RTABMAP_EXP rtabmap::util3d::appendMesh (pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudA, std::vector< pcl::Vertices > &polygonsA, const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloudB, const std::vector< pcl::Vertices > &polygonsB)
void RTABMAP_EXP rtabmap::util3d::appendMesh (pcl::PointCloud< pcl::PointXYZRGB > &cloudA, std::vector< pcl::Vertices > &polygonsA, const pcl::PointCloud< pcl::PointXYZRGB > &cloudB, const std::vector< pcl::Vertices > &polygonsB)
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::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))
pcl::PointCloud< pcl::Normal >::Ptr rtabmap::util3d::computeFastOrganizedNormals (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, float maxDepthChangeFactor=0.02f, float normalSmoothingSize=10.0f, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
pcl::PointCloud< pcl::Normal >
::Ptr RTABMAP_EXP 
rtabmap::util3d::computeNormals (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int normalKSearch=20, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
pcl::PointCloud< pcl::Normal >
::Ptr RTABMAP_EXP 
rtabmap::util3d::computeNormals (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, int normalKSearch=20, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
pcl::PointCloud< pcl::Normal >
::Ptr RTABMAP_EXP 
rtabmap::util3d::computeNormals (const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, int normalKSearch=20, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
pcl::PointCloud< pcl::Normal >
::Ptr RTABMAP_EXP 
rtabmap::util3d::computeNormals (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, int normalKSearch=20, const Eigen::Vector3f &viewPoint=Eigen::Vector3f(0, 0, 0))
pcl::PolygonMesh::Ptr RTABMAP_EXP rtabmap::util3d::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)
void RTABMAP_EXP rtabmap::util3d::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::TextureMesh::Ptr RTABMAP_EXP rtabmap::util3d::createTextureMesh (const pcl::PolygonMesh::Ptr &mesh, const std::map< int, Transform > &poses, const std::map< int, CameraModel > &cameraModels, const std::map< int, cv::Mat > &images, const std::string &tmpDirectory=".", int kNormalSearch=20)
std::vector< pcl::Vertices >
RTABMAP_EXP 
rtabmap::util3d::filterCloseVerticesFromMesh (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr cloud, const std::vector< pcl::Vertices > &polygons, float radius, float angle, bool keepLatestInRadius)
std::vector< pcl::Vertices >
RTABMAP_EXP 
rtabmap::util3d::filterInvalidPolygons (const std::vector< pcl::Vertices > &polygons)
std::map< int, int > RTABMAP_EXP rtabmap::util3d::filterNotUsedVerticesFromMesh (const pcl::PointCloud< pcl::PointXYZRGBNormal > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGBNormal > &outputCloud, std::vector< pcl::Vertices > &outputPolygons)
std::map< int, int > RTABMAP_EXP rtabmap::util3d::filterNotUsedVerticesFromMesh (const pcl::PointCloud< pcl::PointXYZRGB > &cloud, const std::vector< pcl::Vertices > &polygons, pcl::PointCloud< pcl::PointXYZRGB > &outputCloud, std::vector< pcl::Vertices > &outputPolygons)
pcl::PolygonMesh::Ptr RTABMAP_EXP rtabmap::util3d::meshDecimation (const pcl::PolygonMesh::Ptr &mesh, float factor)
pcl::PointCloud
< pcl::PointXYZRGBNormal >
::Ptr RTABMAP_EXP 
rtabmap::util3d::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)
pcl::PointCloud
< pcl::PointXYZRGBNormal >
::Ptr RTABMAP_EXP 
rtabmap::util3d::mls (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, 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)
template<typename pointT >
std::vector< pcl::Vertices > rtabmap::util3d::normalizePolygonsSide (const pcl::PointCloud< pointT > &cloud, const std::vector< pcl::Vertices > &polygons, const pcl::PointXYZ &viewPoint=pcl::PointXYZ(0, 0, 0))
std::vector< pcl::Vertices >
RTABMAP_EXP 
rtabmap::util3d::organizedFastMesh (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, double angleTolerance=M_PI/16, bool quad=true, int trianglePixelSize=2, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0))
std::vector< pcl::Vertices >
RTABMAP_EXP 
rtabmap::util3d::organizedFastMesh (const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, double angleTolerance=M_PI/16, bool quad=true, int trianglePixelSize=2, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0))


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:30