Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
pcl::TextureMapping< PointInT > Class Template Reference

The texture mapping algorithm. More...

#include <texture_mapping.h>

Public Types

typedef pcl::texture_mapping::Camera Camera
 
typedef boost::shared_ptr< const TextureMapping< PointInT > > ConstPtr
 
typedef pcl::octree::OctreePointCloudSearch< PointInT > Octree
 
typedef Octree::ConstPtr OctreeConstPtr
 
typedef Octree::Ptr OctreePtr
 
typedef pcl::PointCloud< PointInT > PointCloud
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef boost::shared_ptr< TextureMapping< PointInT > > Ptr
 
typedef pcl::texture_mapping::UvIndex UvIndex
 

Public Member Functions

bool getPointUVCoordinates (const PointInT &pt, const Camera &cam, Eigen::Vector2f &UV_coordinates)
 computes UV coordinates of point, observed by one particular camera More...
 
bool isPointOccluded (const PointInT &pt, const OctreePtr octree)
 Check if a point is occluded using raycasting on octree. More...
 
void mapMultipleTexturesToMeshUV (pcl::TextureMesh &tex_mesh, pcl::texture_mapping::CameraVector &cams)
 Map textures acquired from a set of cameras onto a mesh. More...
 
void mapTexture2Mesh (pcl::TextureMesh &tex_mesh)
 Map texture to a mesh synthesis algorithm. More...
 
void mapTexture2MeshUV (pcl::TextureMesh &tex_mesh)
 Map texture to a mesh UV mapping. More...
 
void removeOccludedPoints (const PointCloudPtr &input_cloud, PointCloudPtr &filtered_cloud, const double octree_voxel_size, std::vector< int > &visible_indices, std::vector< int > &occluded_indices)
 Remove occluded points from a point cloud. More...
 
void removeOccludedPoints (const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh, const double octree_voxel_size)
 Remove occluded points from a textureMesh. More...
 
void removeOccludedPoints (const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud, const double octree_voxel_size)
 Remove occluded points from a textureMesh. More...
 
void setF (float f)
 Set mesh scale control. More...
 
void setMaxAngle (float maxAngle)
 
void setMaxDepthError (float maxDepthError)
 
void setMaxDistance (float maxDistance)
 
void setMinClusterSize (int size)
 
void setTextureFiles (std::vector< std::string > tex_files)
 Set texture files. More...
 
void setTextureMaterials (TexMaterial tex_material)
 Set texture materials. More...
 
void setVectorField (float x, float y, float z)
 Set vector field. More...
 
void showOcclusions (const PointCloudPtr &input_cloud, pcl::PointCloud< pcl::PointXYZI >::Ptr &colored_cloud, const double octree_voxel_size, const bool show_nb_occlusions=true, const int max_occlusions=4)
 Colors a point cloud, depending on its occlusions. More...
 
void showOcclusions (pcl::TextureMesh &tex_mesh, pcl::PointCloud< pcl::PointXYZI >::Ptr &colored_cloud, double octree_voxel_size, bool show_nb_occlusions=true, int max_occlusions=4)
 Colors the point cloud of a Mesh, depending on its occlusions. More...
 
int sortFacesByCamera (pcl::TextureMesh &tex_mesh, pcl::TextureMesh &sorted_mesh, const pcl::texture_mapping::CameraVector &cameras, const double octree_voxel_size, PointCloud &visible_pts)
 Segment faces by camera visibility. Point-based segmentation. More...
 
 TextureMapping ()
 Constructor. More...
 
void textureMeshwithMultipleCameras (pcl::TextureMesh &mesh, const pcl::texture_mapping::CameraVector &cameras)
 Segment and texture faces by camera visibility. Face-based segmentation. More...
 
bool textureMeshwithMultipleCameras2 (pcl::TextureMesh &mesh, const pcl::texture_mapping::CameraVector &cameras, const rtabmap::ProgressState *callback=0, std::vector< std::map< int, pcl::PointXY > > *vertexToPixels=0)
 
 ~TextureMapping ()
 Destructor. More...
 

Protected Member Functions

bool checkPointInsideTriangle (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, const pcl::PointXY &pt)
 Returns True if a point lays within a triangle. More...
 
std::string getClassName () const
 Class get name method. More...
 
bool getPointUVCoordinates (const PointInT &pt, const Camera &cam, pcl::PointXY &UV_coordinates)
 computes UV coordinates of point, observed by one particular camera More...
 
void getTriangleCircumcenterAndSize (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius)
 Returns the circumcenter of a triangle and the circle's radius. More...
 
void getTriangleCircumcscribedCircleCentroid (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius)
 Returns the centroid of a triangle and the corresponding circumscribed circle's radius. More...
 
bool isFaceProjected (const Camera &camera, const PointInT &p1, const PointInT &p2, const PointInT &p3, pcl::PointXY &proj1, pcl::PointXY &proj2, pcl::PointXY &proj3)
 Returns true if all the vertices of one face are projected on the camera's image plane. More...
 
std::vector< Eigen::Vector2f, Eigen::aligned_allocator< Eigen::Vector2f > > mapTexture2Face (const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3)
 Map texture to a face. More...
 

Protected Attributes

float f_
 mesh scale control. More...
 
float max_angle_
 maximum angle (rad) between camera and polygon to apply a texture More...
 
float max_depth_error_
 maximum depth error between projected point and corresponding depth of the camera to apply a texture More...
 
float max_distance_
 maximum distance between camera and polygon to apply a texture More...
 
int min_cluster_size_
 Remove texture from small polygon clusters. More...
 
std::vector< std::string > tex_files_
 list of texture files More...
 
TexMaterial tex_material_
 list of texture materials More...
 
Eigen::Vector3f vector_field_
 vector field More...
 

Detailed Description

template<typename PointInT>
class pcl::TextureMapping< PointInT >

The texture mapping algorithm.

Author
Khai Tran, Raphael Favier

Definition at line 104 of file texture_mapping.h.

Member Typedef Documentation

template<typename PointInT>
typedef pcl::texture_mapping::Camera pcl::TextureMapping< PointInT >::Camera

Definition at line 119 of file texture_mapping.h.

template<typename PointInT>
typedef boost::shared_ptr< const TextureMapping < PointInT > > pcl::TextureMapping< PointInT >::ConstPtr

Definition at line 109 of file texture_mapping.h.

template<typename PointInT>
typedef pcl::octree::OctreePointCloudSearch<PointInT> pcl::TextureMapping< PointInT >::Octree

Definition at line 115 of file texture_mapping.h.

template<typename PointInT>
typedef Octree::ConstPtr pcl::TextureMapping< PointInT >::OctreeConstPtr

Definition at line 117 of file texture_mapping.h.

template<typename PointInT>
typedef Octree::Ptr pcl::TextureMapping< PointInT >::OctreePtr

Definition at line 116 of file texture_mapping.h.

template<typename PointInT>
typedef pcl::PointCloud<PointInT> pcl::TextureMapping< PointInT >::PointCloud

Definition at line 111 of file texture_mapping.h.

template<typename PointInT>
typedef PointCloud::ConstPtr pcl::TextureMapping< PointInT >::PointCloudConstPtr

Definition at line 113 of file texture_mapping.h.

template<typename PointInT>
typedef PointCloud::Ptr pcl::TextureMapping< PointInT >::PointCloudPtr

Definition at line 112 of file texture_mapping.h.

template<typename PointInT>
typedef boost::shared_ptr< TextureMapping < PointInT > > pcl::TextureMapping< PointInT >::Ptr

Definition at line 108 of file texture_mapping.h.

template<typename PointInT>
typedef pcl::texture_mapping::UvIndex pcl::TextureMapping< PointInT >::UvIndex

Definition at line 120 of file texture_mapping.h.

Constructor & Destructor Documentation

template<typename PointInT>
pcl::TextureMapping< PointInT >::TextureMapping ( )
inline

Constructor.

Definition at line 123 of file texture_mapping.h.

template<typename PointInT>
pcl::TextureMapping< PointInT >::~TextureMapping ( )
inline

Destructor.

Definition at line 129 of file texture_mapping.h.

Member Function Documentation

template<typename PointInT >
bool pcl::TextureMapping< PointInT >::checkPointInsideTriangle ( const pcl::PointXY &  p1,
const pcl::PointXY &  p2,
const pcl::PointXY &  p3,
const pcl::PointXY &  pt 
)
inlineprotected

Returns True if a point lays within a triangle.

see http://www.blackpawn.com/texts/pointinpoly/default.html

Parameters
[in]p1first point of the triangle.
[in]p2second point of the triangle.
[in]p3third point of the triangle.
[in]ptthe querry point.

Definition at line 1538 of file texture_mapping.hpp.

template<typename PointInT>
std::string pcl::TextureMapping< PointInT >::getClassName ( ) const
inlineprotected

Class get name method.

Definition at line 463 of file texture_mapping.h.

template<typename PointInT>
bool pcl::TextureMapping< PointInT >::getPointUVCoordinates ( const PointInT &  pt,
const Camera cam,
Eigen::Vector2f &  UV_coordinates 
)
inline

computes UV coordinates of point, observed by one particular camera

Parameters
[in]ptXYZ point to project on camera plane
[in]camthe camera used for projection
[out]UV_coordinatesthe resulting uv coordinates. Set to (-1.0,-1.0) if the point is not visible by the camera
Returns
false if the point is not visible by the camera

Definition at line 226 of file texture_mapping.h.

template<typename PointInT >
bool pcl::TextureMapping< PointInT >::getPointUVCoordinates ( const PointInT &  pt,
const Camera cam,
pcl::PointXY &  UV_coordinates 
)
inlineprotected

computes UV coordinates of point, observed by one particular camera

Parameters
[in]ptXYZ point to project on camera plane
[in]camthe camera used for projection
[out]UV_coordinatesthe resulting UV coordinates. Set to (-1.0,-1.0) if the point is not visible by the camera
Returns
false if the point is not visible by the camera

Definition at line 1475 of file texture_mapping.hpp.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::getTriangleCircumcenterAndSize ( const pcl::PointXY &  p1,
const pcl::PointXY &  p2,
const pcl::PointXY &  p3,
pcl::PointXY &  circumcenter,
double &  radius 
)
inlineprotected

Returns the circumcenter of a triangle and the circle's radius.

see http://en.wikipedia.org/wiki/Circumcenter for formulas.

Parameters
[in]p1first point of the triangle.
[in]p2second point of the triangle.
[in]p3third point of the triangle.
[out]circumcenterresulting circumcenter
[out]radiusthe radius of the circumscribed circle.

Definition at line 1426 of file texture_mapping.hpp.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::getTriangleCircumcscribedCircleCentroid ( const pcl::PointXY &  p1,
const pcl::PointXY &  p2,
const pcl::PointXY &  p3,
pcl::PointXY &  circumcenter,
double &  radius 
)
inlineprotected

Returns the centroid of a triangle and the corresponding circumscribed circle's radius.

yield a tighter circle than getTriangleCircumcenterAndSize.

Parameters
[in]p1first point of the triangle.
[in]p2second point of the triangle.
[in]p3third point of the triangle.
[out]circumcenterresulting circumcenter
[out]radiusthe radius of the circumscribed circle.

Definition at line 1459 of file texture_mapping.hpp.

template<typename PointInT >
bool pcl::TextureMapping< PointInT >::isFaceProjected ( const Camera camera,
const PointInT &  p1,
const PointInT &  p2,
const PointInT &  p3,
pcl::PointXY &  proj1,
pcl::PointXY &  proj2,
pcl::PointXY &  proj3 
)
inlineprotected

Returns true if all the vertices of one face are projected on the camera's image plane.

Parameters
[in]cameracamera on which to project the face.
[in]p1first point of the face.
[in]p2second point of the face.
[in]p3third point of the face.
[out]proj1UV coordinates corresponding to p1.
[out]proj2UV coordinates corresponding to p2.
[out]proj3UV coordinates corresponding to p3.

Definition at line 1564 of file texture_mapping.hpp.

template<typename PointInT >
bool pcl::TextureMapping< PointInT >::isPointOccluded ( const PointInT &  pt,
const OctreePtr  octree 
)
inline

Check if a point is occluded using raycasting on octree.

Parameters
[in]ptXYZ from which the ray will start (toward the camera)
[in]octreethe octree used for raycasting. It must be initialized with a cloud transformed into the camera's frame
Returns
true if the point is occluded.

Definition at line 394 of file texture_mapping.hpp.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::mapMultipleTexturesToMeshUV ( pcl::TextureMesh &  tex_mesh,
pcl::texture_mapping::CameraVector cams 
)

Map textures acquired from a set of cameras onto a mesh.

With UV mapping, the mesh must be divided into NbCamera + 1 sub-meshes. Each sub-mesh corresponding to the faces visible by one camera. The last submesh containing all non-visible faces

Parameters
[in]tex_meshtexture mesh
[in]camscameras used for UV mapping

Definition at line 296 of file texture_mapping.hpp.

template<typename PointInT >
std::vector< Eigen::Vector2f, Eigen::aligned_allocator< Eigen::Vector2f > > pcl::TextureMapping< PointInT >::mapTexture2Face ( const Eigen::Vector3f &  p1,
const Eigen::Vector3f &  p2,
const Eigen::Vector3f &  p3 
)
protected

Map texture to a face.

Parameters
[in]p1the first point
[in]p2the second point
[in]p3the third point

Definition at line 47 of file texture_mapping.hpp.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::mapTexture2Mesh ( pcl::TextureMesh &  tex_mesh)

Map texture to a mesh synthesis algorithm.

Parameters
[in]tex_meshtexture mesh

Definition at line 145 of file texture_mapping.hpp.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::mapTexture2MeshUV ( pcl::TextureMesh &  tex_mesh)

Map texture to a mesh UV mapping.

Parameters
[in]tex_meshtexture mesh

Definition at line 205 of file texture_mapping.hpp.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::removeOccludedPoints ( const PointCloudPtr input_cloud,
PointCloudPtr filtered_cloud,
const double  octree_voxel_size,
std::vector< int > &  visible_indices,
std::vector< int > &  occluded_indices 
)

Remove occluded points from a point cloud.

Parameters
[in]input_cloudthe cloud on which to perform occlusion detection
[out]filtered_cloudresulting cloud, containing only visible points
[in]octree_voxel_sizeoctree resolution (in meters)
[out]visible_indiceswill contain indices of visible points
[out]occluded_indiceswill contain indices of occluded points

Definition at line 436 of file texture_mapping.hpp.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::removeOccludedPoints ( const pcl::TextureMesh &  tex_mesh,
pcl::TextureMesh &  cleaned_mesh,
const double  octree_voxel_size 
)

Remove occluded points from a textureMesh.

Parameters
[in]tex_meshinput mesh, on witch to perform occlusion detection
[out]cleaned_meshresulting mesh, containing only visible points
[in]octree_voxel_sizeoctree resolution (in meters)

Definition at line 500 of file texture_mapping.hpp.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::removeOccludedPoints ( const pcl::TextureMesh &  tex_mesh,
PointCloudPtr filtered_cloud,
const double  octree_voxel_size 
)

Remove occluded points from a textureMesh.

Parameters
[in]tex_meshinput mesh, on witch to perform occlusion detection
[out]filtered_cloudresulting cloud, containing only visible points
[in]octree_voxel_sizeoctree resolution (in meters)

Definition at line 556 of file texture_mapping.hpp.

template<typename PointInT>
void pcl::TextureMapping< PointInT >::setF ( float  f)
inline

Set mesh scale control.

Parameters
[in]f

Definition at line 137 of file texture_mapping.h.

template<typename PointInT>
void pcl::TextureMapping< PointInT >::setMaxAngle ( float  maxAngle)
inline

Definition at line 186 of file texture_mapping.h.

template<typename PointInT>
void pcl::TextureMapping< PointInT >::setMaxDepthError ( float  maxDepthError)
inline

Definition at line 180 of file texture_mapping.h.

template<typename PointInT>
void pcl::TextureMapping< PointInT >::setMaxDistance ( float  maxDistance)
inline

Definition at line 174 of file texture_mapping.h.

template<typename PointInT>
void pcl::TextureMapping< PointInT >::setMinClusterSize ( int  size)
inline

Definition at line 192 of file texture_mapping.h.

template<typename PointInT>
void pcl::TextureMapping< PointInT >::setTextureFiles ( std::vector< std::string >  tex_files)
inline

Set texture files.

Parameters
[in]tex_fileslist of texture files

Definition at line 159 of file texture_mapping.h.

template<typename PointInT>
void pcl::TextureMapping< PointInT >::setTextureMaterials ( TexMaterial  tex_material)
inline

Set texture materials.

Parameters
[in]tex_materialtexture material

Definition at line 168 of file texture_mapping.h.

template<typename PointInT>
void pcl::TextureMapping< PointInT >::setVectorField ( float  x,
float  y,
float  z 
)
inline

Set vector field.

Parameters
[in]xdata point x
[in]ydata point y
[in]zdata point z

Definition at line 148 of file texture_mapping.h.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::showOcclusions ( const PointCloudPtr input_cloud,
pcl::PointCloud< pcl::PointXYZI >::Ptr colored_cloud,
const double  octree_voxel_size,
const bool  show_nb_occlusions = true,
const int  max_occlusions = 4 
)

Colors a point cloud, depending on its occlusions.

If showNbOcclusions is set to True, each point is colored depending on the number of points occluding it. Else, each point is given a different a 0 value is not occluded, 1 if occluded. By default, the number of occlusions is bounded to 4.

Parameters
[in]input_cloudinput cloud on which occlusions will be computed.
[out]colored_cloudresulting colored cloud showing the number of occlusions per point.
[in]octree_voxel_sizeoctree resolution (in meters).
[in]show_nb_occlusionsIf false, color information will only represent.
[in]max_occlusionsLimit the number of occlusions per point.

Definition at line 668 of file texture_mapping.hpp.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::showOcclusions ( pcl::TextureMesh &  tex_mesh,
pcl::PointCloud< pcl::PointXYZI >::Ptr colored_cloud,
double  octree_voxel_size,
bool  show_nb_occlusions = true,
int  max_occlusions = 4 
)

Colors the point cloud of a Mesh, depending on its occlusions.

If showNbOcclusions is set to True, each point is colored depending on the number of points occluding it. Else, each point is given a different a 0 value is not occluded, 1 if occluded. By default, the number of occlusions is bounded to 4.

Parameters
[in]tex_meshinput mesh on which occlusions will be computed.
[out]colored_cloudresulting colored cloud showing the number of occlusions per point.
[in]octree_voxel_sizeoctree resolution (in meters).
[in]show_nb_occlusionsIf false, color information will only represent.
[in]max_occlusionsLimit the number of occlusions per point.

Definition at line 748 of file texture_mapping.hpp.

template<typename PointInT >
int pcl::TextureMapping< PointInT >::sortFacesByCamera ( pcl::TextureMesh &  tex_mesh,
pcl::TextureMesh &  sorted_mesh,
const pcl::texture_mapping::CameraVector cameras,
const double  octree_voxel_size,
PointCloud visible_pts 
)

Segment faces by camera visibility. Point-based segmentation.

With N camera, faces will be arranged into N+1 groups: 1 for each camera, plus 1 for faces not visible from any camera.

Parameters
[in]tex_meshinput mesh that needs sorting. Must contain only 1 sub-mesh.
[in]sorted_meshresulting mesh, will contain nbCamera + 1 sub-mesh.
[in]camerasvector containing the cameras used for texture mapping.
[in]octree_voxel_sizeoctree resolution (in meters)
[out]visible_ptscloud containing only visible points

Definition at line 571 of file texture_mapping.hpp.

template<typename PointInT >
void pcl::TextureMapping< PointInT >::textureMeshwithMultipleCameras ( pcl::TextureMesh &  mesh,
const pcl::texture_mapping::CameraVector cameras 
)

Segment and texture faces by camera visibility. Face-based segmentation.

With N camera, faces will be arranged into N+1 groups: 1 for each camera, plus 1 for faces not visible from any camera. The mesh will also contain uv coordinates for each face

Parameters
meshinput mesh that needs sorting. Should contain only 1 sub-mesh.
[in]camerasvector containing the cameras used for texture mapping.

Definition at line 760 of file texture_mapping.hpp.

template<typename PointInT >
bool pcl::TextureMapping< PointInT >::textureMeshwithMultipleCameras2 ( pcl::TextureMesh &  mesh,
const pcl::texture_mapping::CameraVector cameras,
const rtabmap::ProgressState callback = 0,
std::vector< std::map< int, pcl::PointXY > > *  vertexToPixels = 0 
)

Definition at line 1053 of file texture_mapping.hpp.

Member Data Documentation

template<typename PointInT>
float pcl::TextureMapping< PointInT >::f_
protected

mesh scale control.

Definition at line 373 of file texture_mapping.h.

template<typename PointInT>
float pcl::TextureMapping< PointInT >::max_angle_
protected

maximum angle (rad) between camera and polygon to apply a texture

Definition at line 391 of file texture_mapping.h.

template<typename PointInT>
float pcl::TextureMapping< PointInT >::max_depth_error_
protected

maximum depth error between projected point and corresponding depth of the camera to apply a texture

Definition at line 388 of file texture_mapping.h.

template<typename PointInT>
float pcl::TextureMapping< PointInT >::max_distance_
protected

maximum distance between camera and polygon to apply a texture

Definition at line 385 of file texture_mapping.h.

template<typename PointInT>
int pcl::TextureMapping< PointInT >::min_cluster_size_
protected

Remove texture from small polygon clusters.

Definition at line 394 of file texture_mapping.h.

template<typename PointInT>
std::vector<std::string> pcl::TextureMapping< PointInT >::tex_files_
protected

list of texture files

Definition at line 379 of file texture_mapping.h.

template<typename PointInT>
TexMaterial pcl::TextureMapping< PointInT >::tex_material_
protected

list of texture materials

Definition at line 382 of file texture_mapping.h.

template<typename PointInT>
Eigen::Vector3f pcl::TextureMapping< PointInT >::vector_field_
protected

vector field

Definition at line 376 of file texture_mapping.h.


The documentation for this class was generated from the following files:


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