texture_mapping.h
Go to the documentation of this file.
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 #ifndef PCL_SURFACE_TEXTURE_MAPPING_H_
41 #define PCL_SURFACE_TEXTURE_MAPPING_H_
42 
43 #include <pcl/surface/reconstruction.h>
44 #include <pcl/common/transforms.h>
45 #include <pcl/TextureMesh.h>
48 #include <rtabmap/utilite/UStl.h>
50 
51 
52 namespace pcl
53 {
54  namespace texture_mapping
55  {
56 
67  struct Camera
68  {
70  center_w (-1), center_h (-1), height (), width (), texture_file () {}
71  Eigen::Affine3f pose;
72  double focal_length;
73  double focal_length_w; // optional
74  double focal_length_h; // optinoal
75  double center_w; // optional
76  double center_h; // optional
77  double height;
78  double width;
79  std::string texture_file;
80  std::vector<double> roi; // [x, y, width, height]
81  cv::Mat depth;
82 
83  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
84  };
85 
88  struct UvIndex
89  {
90  UvIndex () : idx_cloud (), idx_face () {}
91  int idx_cloud; // Index of the PointXYZ in the camera's cloud
92  int idx_face; // Face corresponding to that projection
93  };
94 
95  typedef std::vector<Camera, Eigen::aligned_allocator<Camera> > CameraVector;
96 
97  }
98 
103  template<typename PointInT>
105  {
106  public:
107 
110 
111  typedef pcl::PointCloud<PointInT> PointCloud;
112  typedef typename PointCloud::Ptr PointCloudPtr;
113  typedef typename PointCloud::ConstPtr PointCloudConstPtr;
114 
115  typedef pcl::octree::OctreePointCloudSearch<PointInT> Octree;
116  typedef typename Octree::Ptr OctreePtr;
117  typedef typename Octree::ConstPtr OctreeConstPtr;
118 
121 
124  f_ (), vector_field_ (), tex_files_ (), tex_material_ (), max_distance_(0.0f), max_depth_error_(0.0f), max_angle_(0.0f), min_cluster_size_(50)
125  {
126  }
127 
130  {
131  }
132 
136  inline void
137  setF (float f)
138  {
139  f_ = f;
140  }
141 
147  inline void
148  setVectorField (float x, float y, float z)
149  {
150  vector_field_ = Eigen::Vector3f (x, y, z);
151  // normalize vector field
152  vector_field_ = vector_field_ / std::sqrt (vector_field_.dot (vector_field_));
153  }
154 
158  inline void
159  setTextureFiles (std::vector<std::string> tex_files)
160  {
161  tex_files_ = tex_files;
162  }
163 
167  inline void
168  setTextureMaterials (TexMaterial tex_material)
169  {
170  tex_material_ = tex_material;
171  }
172 
173  inline void
174  setMaxDistance(float maxDistance)
175  {
176  max_distance_ = maxDistance;
177  }
178 
179  inline void
181  {
182  max_depth_error_ = maxDepthError;
183  }
184 
185  inline void
186  setMaxAngle(float maxAngle)
187  {
188  max_angle_ = maxAngle;
189  }
190 
191  inline void
193  {
194  min_cluster_size_ = size;
195  }
196 
200  void
201  mapTexture2Mesh (pcl::TextureMesh &tex_mesh);
202 
206  void
207  mapTexture2MeshUV (pcl::TextureMesh &tex_mesh);
208 
215  void
216  mapMultipleTexturesToMeshUV (pcl::TextureMesh &tex_mesh,
218 
225  inline bool
226  getPointUVCoordinates (const PointInT &pt, const Camera &cam, Eigen::Vector2f &UV_coordinates)
227  {
228  // if the point is in front of the camera
229  if (pt.z > 0 && (max_distance_ <= 0.0f || pt.z < max_distance_))
230  {
231  // compute image center and dimension
232  double sizeX = cam.width;
233  double sizeY = cam.height;
234  double cx, cy;
235  if (cam.center_w > 0)
236  cx = cam.center_w;
237  else
238  cx = (sizeX) / 2.0;
239  if (cam.center_h > 0)
240  cy = cam.center_h;
241  else
242  cy = (sizeY) / 2.0;
243 
244  double focal_x, focal_y;
245  if (cam.focal_length_w > 0)
246  focal_x = cam.focal_length_w;
247  else
248  focal_x = cam.focal_length;
249  if (cam.focal_length_h>0)
250  focal_y = cam.focal_length_h;
251  else
252  focal_y = cam.focal_length;
253 
254  // project point on image frame
255  UV_coordinates[0] = static_cast<float> ((focal_x * (pt.x / pt.z) + cx) / sizeX); //horizontal
256  UV_coordinates[1] = 1.0f - static_cast<float> (((focal_y * (pt.y / pt.z) + cy) / sizeY)); //vertical
257 
258  // point is visible!
259  if (UV_coordinates[0] >= 0.0 && UV_coordinates[0] <= 1.0 && UV_coordinates[1] >= 0.0 && UV_coordinates[1]
260  <= 1.0)
261  return (true);
262  }
263 
264  // point is NOT visible by the camera
265  UV_coordinates[0] = -1.0;
266  UV_coordinates[1] = -1.0;
267  return (false);
268  }
269 
275  inline bool
276  isPointOccluded (const PointInT &pt, const OctreePtr octree);
277 
285  void
286  removeOccludedPoints (const PointCloudPtr &input_cloud,
287  PointCloudPtr &filtered_cloud, const double octree_voxel_size,
288  std::vector<int> &visible_indices, std::vector<int> &occluded_indices);
289 
295  void
296  removeOccludedPoints (const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh, const double octree_voxel_size);
297 
298 
304  void
305  removeOccludedPoints (const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud, const double octree_voxel_size);
306 
307 
316  int
317  sortFacesByCamera (pcl::TextureMesh &tex_mesh,
318  pcl::TextureMesh &sorted_mesh,
319  const pcl::texture_mapping::CameraVector &cameras,
320  const double octree_voxel_size, PointCloud &visible_pts);
321 
332  void
333  showOcclusions (const PointCloudPtr &input_cloud,
334  pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
335  const double octree_voxel_size,
336  const bool show_nb_occlusions = true,
337  const int max_occlusions = 4);
338 
349  void
350  showOcclusions (pcl::TextureMesh &tex_mesh,
351  pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
352  double octree_voxel_size,
353  bool show_nb_occlusions = true,
354  int max_occlusions = 4);
355 
362  void
363  textureMeshwithMultipleCameras (pcl::TextureMesh &mesh,
364  const pcl::texture_mapping::CameraVector &cameras);
365  bool
366  textureMeshwithMultipleCameras2 (pcl::TextureMesh &mesh,
367  const pcl::texture_mapping::CameraVector &cameras,
368  const rtabmap::ProgressState * callback = 0,
369  std::vector<std::map<int, pcl::PointXY> > * vertexToPixels = 0);
370 
371  protected:
373  float f_;
374 
376  Eigen::Vector3f vector_field_;
377 
379  std::vector<std::string> tex_files_;
380 
382  TexMaterial tex_material_;
383 
386 
389 
391  float max_angle_;
392 
395 
401  std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> >
402  mapTexture2Face (const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3);
403 
412  inline void
413  getTriangleCircumcenterAndSize (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius);
414 
415 
424  inline void
425  getTriangleCircumcscribedCircleCentroid ( const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius);
426 
427 
434  inline bool
435  getPointUVCoordinates (const PointInT &pt, const Camera &cam, pcl::PointXY &UV_coordinates);
436 
446  inline bool
447  isFaceProjected (const Camera &camera,
448  const PointInT &p1, const PointInT &p2, const PointInT &p3,
449  pcl::PointXY &proj1, pcl::PointXY &proj2, pcl::PointXY &proj3);
450 
458  inline bool
459  checkPointInsideTriangle (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, const pcl::PointXY &pt);
460 
462  std::string
463  getClassName () const
464  {
465  return ("TextureMapping");
466  }
467 
468  public:
469  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
470  };
471 }
472 
474 
475 #endif /* TEXTURE_MAPPING_H_ */
476 
boost::shared_ptr< const TextureMapping< PointInT > > ConstPtr
float max_distance_
maximum distance between camera and polygon to apply a texture
void setVectorField(float x, float y, float z)
Set vector field.
rtabmap::CameraThread * cam
void setTextureMaterials(TexMaterial tex_material)
Set texture materials.
f
std::vector< Camera, Eigen::aligned_allocator< Camera > > CameraVector
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
TextureMapping()
Constructor.
Definition: CameraRGBD.h:59
const float maxDepthError
Definition: CameraTango.cpp:42
The texture mapping algorithm.
float max_depth_error_
maximum depth error between projected point and corresponding depth of the camera to apply a texture ...
void setMinClusterSize(int size)
Some conversion functions.
pcl::octree::OctreePointCloudSearch< PointInT > Octree
std::vector< double > roi
void setTextureFiles(std::vector< std::string > tex_files)
Set texture files.
int min_cluster_size_
Remove texture from small polygon clusters.
Wrappers of STL for convenient functions.
Structure that links a uv coordinate to its 3D point and face.
Structure to store camera pose and focal length.
~TextureMapping()
Destructor.
Octree::ConstPtr OctreeConstPtr
pcl::PointCloud< PointInT > PointCloud
PointCloud::Ptr PointCloudPtr
void setMaxDepthError(float maxDepthError)
float max_angle_
maximum angle (rad) between camera and polygon to apply a texture
std::string getClassName() const
Class get name method.
float f_
mesh scale control.
TexMaterial tex_material_
list of texture materials
std::vector< std::string > tex_files_
list of texture files
ULogger class and convenient macros.
pcl::texture_mapping::Camera Camera
void setMaxAngle(float maxAngle)
Eigen::Vector3f vector_field_
vector field
bool getPointUVCoordinates(const PointInT &pt, const Camera &cam, Eigen::Vector2f &UV_coordinates)
computes UV coordinates of point, observed by one particular camera
void setMaxDistance(float maxDistance)
void setF(float f)
Set mesh scale control.
PointCloud::ConstPtr PointCloudConstPtr
pcl::texture_mapping::UvIndex UvIndex
boost::shared_ptr< TextureMapping< PointInT > > Ptr


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