The texture mapping algorithm. More...
#include <texture_mapping.h>
Public Types | |
typedef pcl::texture_mapping::Camera | Camera |
typedef boost::shared_ptr < const 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 < PointInT > | Ptr |
typedef pcl::texture_mapping::UvIndex | UvIndex |
Public Member Functions | |
bool | getPointUVCoordinates (const pcl::PointXYZ &pt, const Camera &cam, Eigen::Vector2f &UV_coordinates) |
computes UV coordinates of point, observed by one particular camera | |
bool | isPointOccluded (const pcl::PointXYZ &pt, const OctreePtr octree) |
Check if a point is occluded using raycasting on octree. | |
void | mapMultipleTexturesToMeshUV (pcl::TextureMesh &tex_mesh, pcl::texture_mapping::CameraVector &cams) |
map textures aquired from a set of cameras onto a mesh. | |
void | mapTexture2Mesh (pcl::TextureMesh &tex_mesh) |
Map texture to a mesh synthesis algorithm. | |
void | mapTexture2MeshUV (pcl::TextureMesh &tex_mesh) |
map texture to a mesh UV mapping | |
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. | |
void | removeOccludedPoints (const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh, const double octree_voxel_size) |
Remove occluded points from a textureMesh. | |
void | removeOccludedPoints (const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud, const double octree_voxel_size) |
Remove occluded points from a textureMesh. | |
void | setF (float f) |
Set mesh scale control. | |
void | setTextureFiles (std::vector< std::string > tex_files) |
Set texture files. | |
void | setTextureMaterials (TexMaterial tex_material) |
Set texture materials. | |
void | setVectorField (float x, float y, float z) |
Set vector field. | |
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. | |
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. | |
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. | |
TextureMapping () | |
Constructor. | |
void | textureMeshwithMultipleCameras (pcl::TextureMesh &mesh, const pcl::texture_mapping::CameraVector &cameras) |
Segment and texture faces by camera visibility. Face-based segmentation. | |
~TextureMapping () | |
Destructor. | |
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. | |
std::string | getClassName () const |
Class get name method. | |
bool | getPointUVCoordinates (const pcl::PointXYZ &pt, const Camera &cam, pcl::PointXY &UV_coordinates) |
computes UV coordinates of point, observed by one particular camera | |
void | getTriangleCircumcenterAndSize (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circomcenter, double &radius) |
Returns the circumcenter of a triangle and the circle's radius. | |
bool | isFaceProjected (const Camera &camera, const pcl::PointXYZ &p1, const pcl::PointXYZ &p2, const pcl::PointXYZ &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. | |
std::vector< Eigen::Vector2f > | mapTexture2Face (const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3) |
Map texture to a face. | |
Protected Attributes | |
float | f_ |
mesh scale control. | |
std::vector< std::string > | tex_files_ |
list of texture files | |
TexMaterial | tex_material_ |
list of texture materials | |
Eigen::Vector3f | vector_field_ |
vector field |
The texture mapping algorithm.
Definition at line 84 of file texture_mapping.h.
typedef pcl::texture_mapping::Camera pcl::TextureMapping< PointInT >::Camera |
Definition at line 99 of file texture_mapping.h.
typedef boost::shared_ptr< const PointInT > pcl::TextureMapping< PointInT >::ConstPtr |
Definition at line 89 of file texture_mapping.h.
typedef pcl::octree::OctreePointCloudSearch<PointInT> pcl::TextureMapping< PointInT >::Octree |
Definition at line 95 of file texture_mapping.h.
typedef Octree::ConstPtr pcl::TextureMapping< PointInT >::OctreeConstPtr |
Definition at line 97 of file texture_mapping.h.
typedef Octree::Ptr pcl::TextureMapping< PointInT >::OctreePtr |
Definition at line 96 of file texture_mapping.h.
typedef pcl::PointCloud<PointInT> pcl::TextureMapping< PointInT >::PointCloud |
Definition at line 91 of file texture_mapping.h.
typedef PointCloud::ConstPtr pcl::TextureMapping< PointInT >::PointCloudConstPtr |
Definition at line 93 of file texture_mapping.h.
typedef PointCloud::Ptr pcl::TextureMapping< PointInT >::PointCloudPtr |
Definition at line 92 of file texture_mapping.h.
typedef boost::shared_ptr< PointInT > pcl::TextureMapping< PointInT >::Ptr |
Definition at line 88 of file texture_mapping.h.
typedef pcl::texture_mapping::UvIndex pcl::TextureMapping< PointInT >::UvIndex |
Definition at line 100 of file texture_mapping.h.
pcl::TextureMapping< PointInT >::TextureMapping | ( | ) | [inline] |
Constructor.
Definition at line 103 of file texture_mapping.h.
pcl::TextureMapping< PointInT >::~TextureMapping | ( | ) | [inline] |
Destructor.
Definition at line 109 of file texture_mapping.h.
bool pcl::TextureMapping< PointInT >::checkPointInsideTriangle | ( | const pcl::PointXY & | p1, |
const pcl::PointXY & | p2, | ||
const pcl::PointXY & | p3, | ||
const pcl::PointXY & | pt | ||
) | [inline, protected] |
Returns True if a point lays within a triangle.
see http://www.blackpawn.com/texts/pointinpoly/default.html
[in] | p1 | first point of the triangle. |
[in] | p2 | second point of the triangle. |
[in] | p3 | third point of the triangle. |
[in] | pt | the querry point. |
Definition at line 1047 of file texture_mapping.hpp.
std::string pcl::TextureMapping< PointInT >::getClassName | ( | ) | const [inline, protected] |
Class get name method.
Definition at line 375 of file texture_mapping.h.
bool pcl::TextureMapping< PointInT >::getPointUVCoordinates | ( | const pcl::PointXYZ & | pt, |
const Camera & | cam, | ||
Eigen::Vector2f & | UV_coordinates | ||
) | [inline] |
computes UV coordinates of point, observed by one particular camera
[in] | pt | XYZ point to project on camera plane |
[in] | cam | the camera used for projection |
[out] | UV_coordinates | the resulting uv coordinates. Set to (-1.0,-1.0) if the point is not visible by the camera |
Definition at line 182 of file texture_mapping.h.
bool pcl::TextureMapping< PointInT >::getPointUVCoordinates | ( | const pcl::PointXYZ & | pt, |
const Camera & | cam, | ||
pcl::PointXY & | UV_coordinates | ||
) | [inline, protected] |
computes UV coordinates of point, observed by one particular camera
[in] | pt | XYZ point to project on camera plane |
[in] | cam | the camera used for projection |
[out] | UV_coordinates | the resulting UV coordinates. Set to (-1.0,-1.0) if the point is not visible by the camera |
Definition at line 1020 of file texture_mapping.hpp.
void pcl::TextureMapping< PointInT >::getTriangleCircumcenterAndSize | ( | const pcl::PointXY & | p1, |
const pcl::PointXY & | p2, | ||
const pcl::PointXY & | p3, | ||
pcl::PointXY & | circomcenter, | ||
double & | radius | ||
) | [inline, protected] |
Returns the circumcenter of a triangle and the circle's radius.
see http://en.wikipedia.org/wiki/Circumcenter for formulas.
[in] | p1 | first point of the triangle. |
[in] | p2 | second point of the triangle. |
[in] | p3 | third point of the triangle. |
[out] | circumcenter | resulting circumcenter |
[out] | radius | the radius of the circumscribed circle. |
Definition at line 987 of file texture_mapping.hpp.
bool pcl::TextureMapping< PointInT >::isFaceProjected | ( | const Camera & | camera, |
const pcl::PointXYZ & | p1, | ||
const pcl::PointXYZ & | p2, | ||
const pcl::PointXYZ & | p3, | ||
pcl::PointXY & | proj1, | ||
pcl::PointXY & | proj2, | ||
pcl::PointXY & | proj3 | ||
) | [inline, protected] |
Returns true if all the vertices of one face are projected on the camera's image plane.
[in] | camera | camera on which to project the face. |
[in] | p1 | first point of the face. |
[in] | p2 | second point of the face. |
[in] | p3 | third point of the face. |
[out] | proj1 | UV coordinates corresponding to p1. |
[out] | proj2 | UV coordinates corresponding to p2. |
[out] | proj3 | UV coordinates corresponding to p3. |
Definition at line 1073 of file texture_mapping.hpp.
bool pcl::TextureMapping< PointInT >::isPointOccluded | ( | const pcl::PointXYZ & | pt, |
const OctreePtr | octree | ||
) | [inline] |
Check if a point is occluded using raycasting on octree.
[in] | pt | XYZ from which the ray will start (toward the camera) |
[in] | octree | the octree used for raycasting. It must be initialized with a cloud transformed into the camera's frame |
Definition at line 376 of file texture_mapping.hpp.
void pcl::TextureMapping< PointInT >::mapMultipleTexturesToMeshUV | ( | pcl::TextureMesh & | tex_mesh, |
pcl::texture_mapping::CameraVector & | cams | ||
) |
map textures aquired 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
[in] | tex_mesh | texture mesh |
[in] | cams | cameras used for UV mapping |
Definition at line 286 of file texture_mapping.hpp.
std::vector< Eigen::Vector2f > pcl::TextureMapping< PointInT >::mapTexture2Face | ( | const Eigen::Vector3f & | p1, |
const Eigen::Vector3f & | p2, | ||
const Eigen::Vector3f & | p3 | ||
) | [protected] |
Map texture to a face.
[in] | p1 | the first point |
[in] | p2 | the second point |
[in] | p3 | the third point |
Definition at line 45 of file texture_mapping.hpp.
void pcl::TextureMapping< PointInT >::mapTexture2Mesh | ( | pcl::TextureMesh & | tex_mesh | ) |
Map texture to a mesh synthesis algorithm.
[in] | tex_mesh | texture mesh |
Definition at line 143 of file texture_mapping.hpp.
void pcl::TextureMapping< PointInT >::mapTexture2MeshUV | ( | pcl::TextureMesh & | tex_mesh | ) |
map texture to a mesh UV mapping
[in] | tex_mesh | texture mesh |
Definition at line 199 of file texture_mapping.hpp.
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.
[in] | input_cloud | the cloud on which to perform occlusion detection |
[out] | filtered_cloud | resulting cloud, containing only visible points |
[in] | octree_voxel_size | octree resolution (in meters) |
[out] | visible_indices | will contain indices of visible points |
[out] | occluded_indices | will contain indices of occluded points |
Definition at line 418 of file texture_mapping.hpp.
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.
[in] | tex_mesh | input mesh, on witch to perform occlusion detection |
[out] | cleaned_mesh | resulting mesh, containing only visible points |
[in] | octree_voxel_size | octree resolution (in meters) |
Definition at line 482 of file texture_mapping.hpp.
void pcl::TextureMapping< PointInT >::removeOccludedPoints | ( | const pcl::TextureMesh & | tex_mesh, |
PointCloudPtr & | filtered_cloud, | ||
const double | octree_voxel_size | ||
) |
Remove occluded points from a textureMesh.
[in] | tex_mesh | input mesh, on witch to perform occlusion detection |
[out] | filtered_cloud | resulting cloud, containing only visible points |
[in] | octree_voxel_size | octree resolution (in meters) |
Definition at line 538 of file texture_mapping.hpp.
void pcl::TextureMapping< PointInT >::setF | ( | float | f | ) | [inline] |
void pcl::TextureMapping< PointInT >::setTextureFiles | ( | std::vector< std::string > | tex_files | ) | [inline] |
Set texture files.
[in] | tex_files | list of texture files |
Definition at line 139 of file texture_mapping.h.
void pcl::TextureMapping< PointInT >::setTextureMaterials | ( | TexMaterial | tex_material | ) | [inline] |
Set texture materials.
[in] | tex_material | texture material |
Definition at line 148 of file texture_mapping.h.
void pcl::TextureMapping< PointInT >::setVectorField | ( | float | x, |
float | y, | ||
float | z | ||
) | [inline] |
Set vector field.
[in] | x | data point x |
[in] | y | data point y |
[in] | z | data point z |
Definition at line 128 of file texture_mapping.h.
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.
[in] | input_cloud | input cloud on which occlusions will be computed. |
[out] | colored_cloud | resulting colored cloud showing the number of occlusions per point. |
[in] | octree_voxel_size | octree resolution (in meters). |
[in] | show_nb_occlusions | If false, color information will only represent. |
[in] | max_occlusions | Limit the number of occlusions per point. |
Definition at line 650 of file texture_mapping.hpp.
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.
[in] | tex_mesh | input mesh on which occlusions will be computed. |
[out] | colored_cloud | resulting colored cloud showing the number of occlusions per point. |
[in] | octree_voxel_size | octree resolution (in meters). |
[in] | show_nb_occlusions | If false, color information will only represent. |
[in] | max_occlusions | Limit the number of occlusions per point. |
Definition at line 730 of file texture_mapping.hpp.
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.
[in] | tex_mesh | input mesh that needs sorting. Must contain only 1 sub-mesh. |
[in] | sorted_mesh | resulting mesh, will contain nbCamera + 1 sub-mesh. |
[in] | cameras | vector containing the cameras used for texture mapping. |
[in] | octree_voxel_size | octree resolution (in meters) |
[out] | visible_pts | cloud containing only visible points |
Definition at line 553 of file texture_mapping.hpp.
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
in/out] | tex_mesh input mesh that needs sorting. Should contain only 1 sub-mesh. | |
[in] | cameras | vector containing the cameras used for texture mapping. |
Definition at line 742 of file texture_mapping.hpp.
float pcl::TextureMapping< PointInT >::f_ [protected] |
mesh scale control.
Definition at line 310 of file texture_mapping.h.
std::vector<std::string> pcl::TextureMapping< PointInT >::tex_files_ [protected] |
list of texture files
Definition at line 316 of file texture_mapping.h.
TexMaterial pcl::TextureMapping< PointInT >::tex_material_ [protected] |
list of texture materials
Definition at line 319 of file texture_mapping.h.
Eigen::Vector3f pcl::TextureMapping< PointInT >::vector_field_ [protected] |
vector field
Definition at line 313 of file texture_mapping.h.