Point Cloud Library (PCL)  1.11.1-dev
texture_mapping.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * $Id$
37  *
38  */
39 
40 #pragma once
41 
42 #include <pcl/memory.h>
43 #include <pcl/pcl_macros.h>
44 #include <pcl/surface/reconstruction.h>
45 #include <pcl/common/transforms.h>
46 #include <pcl/TextureMesh.h>
47 #include <pcl/octree/octree_search.h> // for OctreePointCloudSearch
48 
49 
50 namespace pcl
51 {
52  namespace texture_mapping
53  {
54 
55  /** \brief Structure to store camera pose and focal length.
56  *
57  * One can assign a value to focal_length, to be used along
58  * both camera axes or, optionally, axis-specific values
59  * (focal_length_w and focal_length_h). Optionally, one can
60  * also specify center-of-focus using parameters
61  * center_w and center_h. If the center-of-focus is not
62  * specified, it will be set to the geometric center of
63  * the camera, as defined by the width and height parameters.
64  */
65  struct Camera
66  {
68  center_w (-1), center_h (-1), height (), width () {}
69  Eigen::Affine3f pose;
70  double focal_length;
71  double focal_length_w; // optional
72  double focal_length_h; // optinoal
73  double center_w; // optional
74  double center_h; // optional
75  double height;
76  double width;
77  std::string texture_file;
78 
80  };
81 
82  /** \brief Structure that links a uv coordinate to its 3D point and face.
83  */
84  struct UvIndex
85  {
86  UvIndex () : idx_cloud (), idx_face () {}
87  int idx_cloud; // Index of the PointXYZ in the camera's cloud
88  int idx_face; // Face corresponding to that projection
89  };
90 
91  using CameraVector = std::vector<Camera, Eigen::aligned_allocator<Camera> >;
92 
93  }
94 
95  /** \brief The texture mapping algorithm
96  * \author Khai Tran, Raphael Favier
97  * \ingroup surface
98  */
99  template<typename PointInT>
101  {
102  public:
103 
104  using Ptr = shared_ptr<TextureMapping<PointInT> >;
105  using ConstPtr = shared_ptr<const TextureMapping<PointInT> >;
106 
108  using PointCloudPtr = typename PointCloud::Ptr;
110 
112  using OctreePtr = typename Octree::Ptr;
114 
117 
118  /** \brief Constructor. */
120  f_ ()
121  {
122  }
123 
124  /** \brief Destructor. */
126  {
127  }
128 
129  /** \brief Set mesh scale control
130  * \param[in] f
131  */
132  inline void
133  setF (float f)
134  {
135  f_ = f;
136  }
137 
138  /** \brief Set vector field
139  * \param[in] x data point x
140  * \param[in] y data point y
141  * \param[in] z data point z
142  */
143  inline void
144  setVectorField (float x, float y, float z)
145  {
146  vector_field_ = Eigen::Vector3f (x, y, z);
147  // normalize vector field
148  vector_field_ /= std::sqrt (vector_field_.dot (vector_field_));
149  }
150 
151  /** \brief Set texture files
152  * \param[in] tex_files list of texture files
153  */
154  inline void
155  setTextureFiles (std::vector<std::string> tex_files)
156  {
157  tex_files_ = tex_files;
158  }
159 
160  /** \brief Set texture materials
161  * \param[in] tex_material texture material
162  */
163  inline void
165  {
166  tex_material_ = tex_material;
167  }
168 
169  /** \brief Map texture to a mesh synthesis algorithm
170  * \param[in] tex_mesh texture mesh
171  */
172  void
173  mapTexture2Mesh (pcl::TextureMesh &tex_mesh);
174 
175  /** \brief Map texture to a mesh UV mapping
176  * \param[in] tex_mesh texture mesh
177  */
178  void
180 
181  /** \brief Map textures acquired from a set of cameras onto a mesh.
182  * \details With UV mapping, the mesh must be divided into NbCamera + 1 sub-meshes.
183  * Each sub-mesh corresponding to the faces visible by one camera. The last submesh containing all non-visible faces
184  * \param[in] tex_mesh texture mesh
185  * \param[in] cams cameras used for UV mapping
186  */
187  void
190 
191  /** \brief computes UV coordinates of point, observed by one particular camera
192  * \param[in] pt XYZ point to project on camera plane
193  * \param[in] cam the camera used for projection
194  * \param[out] UV_coordinates the resulting uv coordinates. Set to (-1.0,-1.0) if the point is not visible by the camera
195  * \returns false if the point is not visible by the camera
196  */
197  inline bool
198  getPointUVCoordinates (const PointInT &pt, const Camera &cam, Eigen::Vector2f &UV_coordinates)
199  {
200  // if the point is in front of the camera
201  if (pt.z > 0)
202  {
203  // compute image center and dimension
204  double sizeX = cam.width;
205  double sizeY = cam.height;
206  double cx, cy;
207  if (cam.center_w > 0)
208  cx = cam.center_w;
209  else
210  cx = (sizeX) / 2.0;
211  if (cam.center_h > 0)
212  cy = cam.center_h;
213  else
214  cy = (sizeY) / 2.0;
215 
216  double focal_x, focal_y;
217  if (cam.focal_length_w > 0)
218  focal_x = cam.focal_length_w;
219  else
220  focal_x = cam.focal_length;
221  if (cam.focal_length_h>0)
222  focal_y = cam.focal_length_h;
223  else
224  focal_y = cam.focal_length;
225 
226  // project point on image frame
227  UV_coordinates[0] = static_cast<float> ((focal_x * (pt.x / pt.z) + cx) / sizeX); //horizontal
228  UV_coordinates[1] = 1.0f - static_cast<float> (((focal_y * (pt.y / pt.z) + cy) / sizeY)); //vertical
229 
230  // point is visible!
231  if (UV_coordinates[0] >= 0.0 && UV_coordinates[0] <= 1.0 && UV_coordinates[1] >= 0.0 && UV_coordinates[1]
232  <= 1.0)
233  return (true);
234  }
235 
236  // point is NOT visible by the camera
237  UV_coordinates[0] = -1.0;
238  UV_coordinates[1] = -1.0;
239  return (false);
240  }
241 
242  /** \brief Check if a point is occluded using raycasting on octree.
243  * \param[in] pt XYZ from which the ray will start (toward the camera)
244  * \param[in] octree the octree used for raycasting. It must be initialized with a cloud transformed into the camera's frame
245  * \returns true if the point is occluded.
246  */
247  inline bool
248  isPointOccluded (const PointInT &pt, const OctreePtr octree);
249 
250  /** \brief Remove occluded points from a point cloud
251  * \param[in] input_cloud the cloud on which to perform occlusion detection
252  * \param[out] filtered_cloud resulting cloud, containing only visible points
253  * \param[in] octree_voxel_size octree resolution (in meters)
254  * \param[out] visible_indices will contain indices of visible points
255  * \param[out] occluded_indices will contain indices of occluded points
256  */
257  void
258  removeOccludedPoints (const PointCloudPtr &input_cloud,
259  PointCloudPtr &filtered_cloud, const double octree_voxel_size,
260  pcl::Indices &visible_indices, pcl::Indices &occluded_indices);
261 
262  /** \brief Remove occluded points from a textureMesh
263  * \param[in] tex_mesh input mesh, on witch to perform occlusion detection
264  * \param[out] cleaned_mesh resulting mesh, containing only visible points
265  * \param[in] octree_voxel_size octree resolution (in meters)
266  */
267  void
268  removeOccludedPoints (const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh, const double octree_voxel_size);
269 
270 
271  /** \brief Remove occluded points from a textureMesh
272  * \param[in] tex_mesh input mesh, on witch to perform occlusion detection
273  * \param[out] filtered_cloud resulting cloud, containing only visible points
274  * \param[in] octree_voxel_size octree resolution (in meters)
275  */
276  void
277  removeOccludedPoints (const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud, const double octree_voxel_size);
278 
279 
280  /** \brief Segment faces by camera visibility. Point-based segmentation.
281  * \details With N camera, faces will be arranged into N+1 groups: 1 for each camera, plus 1 for faces not visible from any camera.
282  * \param[in] tex_mesh input mesh that needs sorting. Must contain only 1 sub-mesh.
283  * \param[in] sorted_mesh resulting mesh, will contain nbCamera + 1 sub-mesh.
284  * \param[in] cameras vector containing the cameras used for texture mapping.
285  * \param[in] octree_voxel_size octree resolution (in meters)
286  * \param[out] visible_pts cloud containing only visible points
287  */
288  int
290  pcl::TextureMesh &sorted_mesh,
291  const pcl::texture_mapping::CameraVector &cameras,
292  const double octree_voxel_size, PointCloud &visible_pts);
293 
294  /** \brief Colors a point cloud, depending on its occlusions.
295  * \details If showNbOcclusions is set to True, each point is colored depending on the number of points occluding it.
296  * Else, each point is given a different a 0 value is not occluded, 1 if occluded.
297  * By default, the number of occlusions is bounded to 4.
298  * \param[in] input_cloud input cloud on which occlusions will be computed.
299  * \param[out] colored_cloud resulting colored cloud showing the number of occlusions per point.
300  * \param[in] octree_voxel_size octree resolution (in meters).
301  * \param[in] show_nb_occlusions If false, color information will only represent.
302  * \param[in] max_occlusions Limit the number of occlusions per point.
303  */
304  void
305  showOcclusions (const PointCloudPtr &input_cloud,
307  const double octree_voxel_size,
308  const bool show_nb_occlusions = true,
309  const int max_occlusions = 4);
310 
311  /** \brief Colors the point cloud of a Mesh, depending on its occlusions.
312  * \details If showNbOcclusions is set to True, each point is colored depending on the number of points occluding it.
313  * Else, each point is given a different a 0 value is not occluded, 1 if occluded.
314  * By default, the number of occlusions is bounded to 4.
315  * \param[in] tex_mesh input mesh on which occlusions will be computed.
316  * \param[out] colored_cloud resulting colored cloud showing the number of occlusions per point.
317  * \param[in] octree_voxel_size octree resolution (in meters).
318  * \param[in] show_nb_occlusions If false, color information will only represent.
319  * \param[in] max_occlusions Limit the number of occlusions per point.
320  */
321  void
322  showOcclusions (pcl::TextureMesh &tex_mesh,
324  double octree_voxel_size,
325  bool show_nb_occlusions = true,
326  int max_occlusions = 4);
327 
328  /** \brief Segment and texture faces by camera visibility. Face-based segmentation.
329  * \details With N camera, faces will be arranged into N+1 groups: 1 for each camera, plus 1 for faces not visible from any camera.
330  * The mesh will also contain uv coordinates for each face
331  * \param mesh input mesh that needs sorting. Should contain only 1 sub-mesh.
332  * \param[in] cameras vector containing the cameras used for texture mapping.
333  */
334  void
336  const pcl::texture_mapping::CameraVector &cameras);
337 
338  protected:
339  /** \brief mesh scale control. */
340  float f_;
341 
342  /** \brief vector field */
343  Eigen::Vector3f vector_field_;
344 
345  /** \brief list of texture files */
346  std::vector<std::string> tex_files_;
347 
348  /** \brief list of texture materials */
350 
351  /** \brief Map texture to a face
352  * \param[in] p1 the first point
353  * \param[in] p2 the second point
354  * \param[in] p3 the third point
355  */
356  std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> >
357  mapTexture2Face (const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3);
358 
359  /** \brief Returns the circumcenter of a triangle and the circle's radius.
360  * \details see http://en.wikipedia.org/wiki/Circumcenter for formulas.
361  * \param[in] p1 first point of the triangle.
362  * \param[in] p2 second point of the triangle.
363  * \param[in] p3 third point of the triangle.
364  * \param[out] circumcenter resulting circumcenter
365  * \param[out] radius the radius of the circumscribed circle.
366  */
367  inline void
368  getTriangleCircumcenterAndSize (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius);
369 
370 
371  /** \brief Returns the centroid of a triangle and the corresponding circumscribed circle's radius.
372  * \details yield a tighter circle than getTriangleCircumcenterAndSize.
373  * \param[in] p1 first point of the triangle.
374  * \param[in] p2 second point of the triangle.
375  * \param[in] p3 third point of the triangle.
376  * \param[out] circumcenter resulting circumcenter
377  * \param[out] radius the radius of the circumscribed circle.
378  */
379  inline void
380  getTriangleCircumcscribedCircleCentroid ( const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius);
381 
382 
383  /** \brief computes UV coordinates of point, observed by one particular camera
384  * \param[in] pt XYZ point to project on camera plane
385  * \param[in] cam the camera used for projection
386  * \param[out] UV_coordinates the resulting UV coordinates. Set to (-1.0,-1.0) if the point is not visible by the camera
387  * \returns false if the point is not visible by the camera
388  */
389  inline bool
390  getPointUVCoordinates (const PointInT &pt, const Camera &cam, pcl::PointXY &UV_coordinates);
391 
392  /** \brief Returns true if all the vertices of one face are projected on the camera's image plane.
393  * \param[in] camera camera on which to project the face.
394  * \param[in] p1 first point of the face.
395  * \param[in] p2 second point of the face.
396  * \param[in] p3 third point of the face.
397  * \param[out] proj1 UV coordinates corresponding to p1.
398  * \param[out] proj2 UV coordinates corresponding to p2.
399  * \param[out] proj3 UV coordinates corresponding to p3.
400  */
401  inline bool
402  isFaceProjected (const Camera &camera,
403  const PointInT &p1, const PointInT &p2, const PointInT &p3,
404  pcl::PointXY &proj1, pcl::PointXY &proj2, pcl::PointXY &proj3);
405 
406  /** \brief Returns True if a point lays within a triangle
407  * \details see http://www.blackpawn.com/texts/pointinpoly/default.html
408  * \param[in] p1 first point of the triangle.
409  * \param[in] p2 second point of the triangle.
410  * \param[in] p3 third point of the triangle.
411  * \param[in] pt the querry point.
412  */
413  inline bool
414  checkPointInsideTriangle (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, const pcl::PointXY &pt);
415 
416  /** \brief Class get name method. */
417  std::string
418  getClassName () const
419  {
420  return ("TextureMapping");
421  }
422 
423  public:
425  };
426 }
pcl::TextureMapping::checkPointInsideTriangle
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.
Definition: texture_mapping.hpp:1044
pcl::TextureMapping::tex_material_
TexMaterial tex_material_
list of texture materials
Definition: texture_mapping.h:349
pcl_macros.h
Defines all the PCL and non-PCL macros used.
pcl::texture_mapping::Camera::width
double width
Definition: texture_mapping.h:76
pcl::texture_mapping::Camera::focal_length_w
double focal_length_w
Definition: texture_mapping.h:71
pcl
Definition: convolution.h:46
pcl::texture_mapping::Camera::pose
Eigen::Affine3f pose
Definition: texture_mapping.h:69
pcl::TextureMapping::getTriangleCircumcscribedCircleCentroid
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.
Definition: texture_mapping.hpp:984
pcl::texture_mapping::UvIndex
Structure that links a uv coordinate to its 3D point and face.
Definition: texture_mapping.h:84
pcl::TextureMapping::mapTexture2MeshUV
void mapTexture2MeshUV(pcl::TextureMesh &tex_mesh)
Map texture to a mesh UV mapping.
Definition: texture_mapping.hpp:201
pcl::TextureMapping::textureMeshwithMultipleCameras
void textureMeshwithMultipleCameras(pcl::TextureMesh &mesh, const pcl::texture_mapping::CameraVector &cameras)
Segment and texture faces by camera visibility.
Definition: texture_mapping.hpp:710
pcl::TextureMapping::setTextureFiles
void setTextureFiles(std::vector< std::string > tex_files)
Set texture files.
Definition: texture_mapping.h:155
pcl::texture_mapping::Camera::focal_length_h
double focal_length_h
Definition: texture_mapping.h:72
pcl::PointCloud< PointInT >
pcl::texture_mapping::UvIndex::idx_face
int idx_face
Definition: texture_mapping.h:88
pcl::TextureMapping::isFaceProjected
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.
Definition: texture_mapping.hpp:1070
pcl::texture_mapping::Camera::height
double height
Definition: texture_mapping.h:75
pcl::TextureMapping::isPointOccluded
bool isPointOccluded(const PointInT &pt, const OctreePtr octree)
Check if a point is occluded using raycasting on octree.
Definition: texture_mapping.hpp:367
pcl::texture_mapping::Camera::Camera
Camera()
Definition: texture_mapping.h:67
pcl::TexMaterial
Definition: TextureMesh.h:49
pcl::texture_mapping::Camera::focal_length
double focal_length
Definition: texture_mapping.h:70
pcl::TextureMapping::vector_field_
Eigen::Vector3f vector_field_
vector field
Definition: texture_mapping.h:343
pcl::texture_mapping::Camera
Structure to store camera pose and focal length.
Definition: texture_mapping.h:65
pcl::TextureMapping::OctreePtr
typename Octree::Ptr OctreePtr
Definition: texture_mapping.h:112
pcl::TextureMapping
The texture mapping algorithm.
Definition: texture_mapping.h:100
pcl::TextureMapping::getPointUVCoordinates
bool getPointUVCoordinates(const PointInT &pt, const Camera &cam, Eigen::Vector2f &UV_coordinates)
computes UV coordinates of point, observed by one particular camera
Definition: texture_mapping.h:198
pcl::texture_mapping::Camera::texture_file
std::string texture_file
Definition: texture_mapping.h:77
pcl::TextureMapping::OctreeConstPtr
typename Octree::ConstPtr OctreeConstPtr
Definition: texture_mapping.h:113
pcl::texture_mapping::Camera::center_w
double center_w
Definition: texture_mapping.h:73
pcl::texture_mapping::CameraVector
std::vector< Camera, Eigen::aligned_allocator< Camera > > CameraVector
Definition: texture_mapping.h:91
pcl::TextureMapping::setTextureMaterials
void setTextureMaterials(TexMaterial tex_material)
Set texture materials.
Definition: texture_mapping.h:164
pcl::TextureMapping::mapTexture2Mesh
void mapTexture2Mesh(pcl::TextureMesh &tex_mesh)
Map texture to a mesh synthesis algorithm.
Definition: texture_mapping.hpp:145
pcl::octree::OctreePointCloudSearch::Ptr
shared_ptr< OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > > Ptr
Definition: octree_search.h:70
PCL_MAKE_ALIGNED_OPERATOR_NEW
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63
pcl::octree::OctreePointCloudSearch::ConstPtr
shared_ptr< const OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > > ConstPtr
Definition: octree_search.h:72
pcl::TextureMapping::TextureMapping
TextureMapping()
Constructor.
Definition: texture_mapping.h:119
pcl::TextureMapping::getClassName
std::string getClassName() const
Class get name method.
Definition: texture_mapping.h:418
pcl::PointXY
A 2D point structure representing Euclidean xy coordinates.
Definition: point_types.hpp:744
pcl::Indices
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:131
pcl::TextureMapping::setVectorField
void setVectorField(float x, float y, float z)
Set vector field.
Definition: texture_mapping.h:144
pcl::TextureMapping::mapTexture2Face
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.
Definition: texture_mapping.hpp:47
pcl::PointCloud< PointInT >::Ptr
shared_ptr< PointCloud< PointInT > > Ptr
Definition: point_cloud.h:406
pcl::TextureMapping::PointCloudConstPtr
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: texture_mapping.h:109
pcl::TextureMapping::showOcclusions
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.
Definition: texture_mapping.hpp:624
pcl::TextureMapping::removeOccludedPoints
void removeOccludedPoints(const PointCloudPtr &input_cloud, PointCloudPtr &filtered_cloud, const double octree_voxel_size, pcl::Indices &visible_indices, pcl::Indices &occluded_indices)
Remove occluded points from a point cloud.
Definition: texture_mapping.hpp:406
pcl::TextureMesh
Definition: TextureMesh.h:88
pcl::texture_mapping::UvIndex::UvIndex
UvIndex()
Definition: texture_mapping.h:86
pcl::TextureMapping::setF
void setF(float f)
Set mesh scale control.
Definition: texture_mapping.h:133
pcl::PointCloud< PointInT >::ConstPtr
shared_ptr< const PointCloud< PointInT > > ConstPtr
Definition: point_cloud.h:407
pcl::TextureMapping::f_
float f_
mesh scale control.
Definition: texture_mapping.h:340
pcl::texture_mapping::Camera::center_h
double center_h
Definition: texture_mapping.h:74
pcl::TextureMapping::mapMultipleTexturesToMeshUV
void mapMultipleTexturesToMeshUV(pcl::TextureMesh &tex_mesh, pcl::texture_mapping::CameraVector &cams)
Map textures acquired from a set of cameras onto a mesh.
Definition: texture_mapping.hpp:287
pcl::TextureMapping::ConstPtr
shared_ptr< const TextureMapping< PointInT > > ConstPtr
Definition: texture_mapping.h:105
pcl::TextureMapping::getTriangleCircumcenterAndSize
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.
Definition: texture_mapping.hpp:951
pcl::TextureMapping::PointCloudPtr
typename PointCloud::Ptr PointCloudPtr
Definition: texture_mapping.h:108
pcl::octree::OctreePointCloudSearch
Octree pointcloud search class
Definition: octree_search.h:57
pcl::TextureMapping::tex_files_
std::vector< std::string > tex_files_
list of texture files
Definition: texture_mapping.h:346
pcl::TextureMapping::Ptr
shared_ptr< TextureMapping< PointInT > > Ptr
Definition: texture_mapping.h:104
pcl::TextureMapping::~TextureMapping
~TextureMapping()
Destructor.
Definition: texture_mapping.h:125
memory.h
Defines functions, macros and traits for allocating and using memory.
pcl::TextureMapping::sortFacesByCamera
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.
Definition: texture_mapping.hpp:538
pcl::texture_mapping::UvIndex::idx_cloud
int idx_cloud
Definition: texture_mapping.h:87