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, bool distanceToCamPolicy=false) |
~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... | |
The texture mapping algorithm.
Definition at line 105 of file texture_mapping.h.
typedef pcl::texture_mapping::Camera pcl::TextureMapping< PointInT >::Camera |
Definition at line 120 of file texture_mapping.h.
typedef boost::shared_ptr< const TextureMapping < PointInT > > pcl::TextureMapping< PointInT >::ConstPtr |
Definition at line 110 of file texture_mapping.h.
typedef pcl::octree::OctreePointCloudSearch<PointInT> pcl::TextureMapping< PointInT >::Octree |
Definition at line 116 of file texture_mapping.h.
typedef Octree::ConstPtr pcl::TextureMapping< PointInT >::OctreeConstPtr |
Definition at line 118 of file texture_mapping.h.
typedef Octree::Ptr pcl::TextureMapping< PointInT >::OctreePtr |
Definition at line 117 of file texture_mapping.h.
typedef pcl::PointCloud<PointInT> pcl::TextureMapping< PointInT >::PointCloud |
Definition at line 112 of file texture_mapping.h.
typedef PointCloud::ConstPtr pcl::TextureMapping< PointInT >::PointCloudConstPtr |
Definition at line 114 of file texture_mapping.h.
typedef PointCloud::Ptr pcl::TextureMapping< PointInT >::PointCloudPtr |
Definition at line 113 of file texture_mapping.h.
typedef boost::shared_ptr< TextureMapping < PointInT > > pcl::TextureMapping< PointInT >::Ptr |
Definition at line 109 of file texture_mapping.h.
typedef pcl::texture_mapping::UvIndex pcl::TextureMapping< PointInT >::UvIndex |
Definition at line 121 of file texture_mapping.h.
|
inline |
Constructor.
Definition at line 124 of file texture_mapping.h.
|
inline |
Destructor.
Definition at line 130 of file texture_mapping.h.
|
inlineprotected |
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 1552 of file texture_mapping.hpp.
|
inlineprotected |
Class get name method.
Definition at line 465 of file texture_mapping.h.
|
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 227 of file texture_mapping.h.
|
inlineprotected |
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 1489 of file texture_mapping.hpp.
|
inlineprotected |
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 1440 of file texture_mapping.hpp.
|
inlineprotected |
Returns the centroid of a triangle and the corresponding circumscribed circle's radius.
yield a tighter circle than getTriangleCircumcenterAndSize.
[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 1473 of file texture_mapping.hpp.
|
inlineprotected |
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 1578 of file texture_mapping.hpp.
|
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 395 of file texture_mapping.hpp.
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
[in] | tex_mesh | texture mesh |
[in] | cams | cameras used for UV mapping |
Definition at line 297 of file texture_mapping.hpp.
|
protected |
Map texture to a face.
[in] | p1 | the first point |
[in] | p2 | the second point |
[in] | p3 | the third point |
Definition at line 48 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 146 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 206 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 437 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 501 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 557 of file texture_mapping.hpp.
|
inline |
|
inline |
Definition at line 187 of file texture_mapping.h.
|
inline |
Definition at line 181 of file texture_mapping.h.
|
inline |
Definition at line 175 of file texture_mapping.h.
|
inline |
Definition at line 193 of file texture_mapping.h.
|
inline |
Set texture files.
[in] | tex_files | list of texture files |
Definition at line 160 of file texture_mapping.h.
|
inline |
Set texture materials.
[in] | tex_material | texture material |
Definition at line 169 of file texture_mapping.h.
|
inline |
Set vector field.
[in] | x | data point x |
[in] | y | data point y |
[in] | z | data point z |
Definition at line 149 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 669 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 749 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 572 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
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 761 of file texture_mapping.hpp.
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 , |
||
bool | distanceToCamPolicy = false |
||
) |
Definition at line 1054 of file texture_mapping.hpp.
|
protected |
mesh scale control.
Definition at line 375 of file texture_mapping.h.
|
protected |
maximum angle (rad) between camera and polygon to apply a texture
Definition at line 393 of file texture_mapping.h.
|
protected |
maximum depth error between projected point and corresponding depth of the camera to apply a texture
Definition at line 390 of file texture_mapping.h.
|
protected |
maximum distance between camera and polygon to apply a texture
Definition at line 387 of file texture_mapping.h.
|
protected |
Remove texture from small polygon clusters.
Definition at line 396 of file texture_mapping.h.
|
protected |
list of texture files
Definition at line 381 of file texture_mapping.h.
|
protected |
list of texture materials
Definition at line 384 of file texture_mapping.h.
|
protected |
vector field
Definition at line 378 of file texture_mapping.h.