texture_mapping.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id$
00037  *
00038  */
00039 
00040 #ifndef PCL_SURFACE_TEXTURE_MAPPING_H_
00041 #define PCL_SURFACE_TEXTURE_MAPPING_H_
00042 
00043 #include <pcl/surface/reconstruction.h>
00044 #include <pcl/common/transforms.h>
00045 #include <pcl/TextureMesh.h>
00046 
00047 
00048 namespace pcl
00049 {
00050   namespace texture_mapping
00051   {
00052         
00054     struct Camera
00055     {
00056       Camera () : pose (), focal_length (), height (), width (), texture_file () {}
00057       Eigen::Affine3f pose;
00058       double focal_length;
00059       double height;
00060       double width;
00061       std::string texture_file;
00062 
00063       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00064     };
00065 
00068     struct UvIndex
00069     {
00070       UvIndex () : idx_cloud (), idx_face () {}
00071       int idx_cloud; // Index of the PointXYZ in the camera's cloud
00072       int idx_face; // Face corresponding to that projection
00073     };
00074     
00075     typedef std::vector<Camera, Eigen::aligned_allocator<Camera> > CameraVector;
00076     
00077   }
00078   
00083   template<typename PointInT>
00084   class TextureMapping
00085   {
00086     public:
00087      
00088       typedef boost::shared_ptr< PointInT > Ptr;
00089       typedef boost::shared_ptr< const PointInT > ConstPtr;
00090 
00091       typedef pcl::PointCloud<PointInT> PointCloud;
00092       typedef typename PointCloud::Ptr PointCloudPtr;
00093       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00094 
00095       typedef pcl::octree::OctreePointCloudSearch<PointInT> Octree;
00096       typedef typename Octree::Ptr OctreePtr;
00097       typedef typename Octree::ConstPtr OctreeConstPtr;
00098       
00099       typedef pcl::texture_mapping::Camera Camera;
00100       typedef pcl::texture_mapping::UvIndex UvIndex;
00101 
00103       TextureMapping () :
00104         f_ (), vector_field_ (), tex_files_ (), tex_material_ ()
00105       {
00106       }
00107 
00109       ~TextureMapping ()
00110       {
00111       }
00112 
00116       inline void
00117       setF (float f)
00118       {
00119         f_ = f;
00120       }
00121 
00127       inline void
00128       setVectorField (float x, float y, float z)
00129       {
00130         vector_field_ = Eigen::Vector3f (x, y, z);
00131         // normalize vector field
00132         vector_field_ = vector_field_ / std::sqrt (vector_field_.dot (vector_field_));
00133       }
00134 
00138       inline void
00139       setTextureFiles (std::vector<std::string> tex_files)
00140       {
00141         tex_files_ = tex_files;
00142       }
00143 
00147       inline void
00148       setTextureMaterials (TexMaterial tex_material)
00149       {
00150         tex_material_ = tex_material;
00151       }
00152 
00156       void
00157       mapTexture2Mesh (pcl::TextureMesh &tex_mesh);
00158 
00162       void
00163       mapTexture2MeshUV (pcl::TextureMesh &tex_mesh);
00164 
00171       void
00172       mapMultipleTexturesToMeshUV (pcl::TextureMesh &tex_mesh, 
00173                                    pcl::texture_mapping::CameraVector &cams);
00174 
00181       inline bool
00182       getPointUVCoordinates (const pcl::PointXYZ &pt, const Camera &cam, Eigen::Vector2f &UV_coordinates)
00183       {
00184         // if the point is in front of the camera
00185         if (pt.z > 0)
00186         {
00187           // compute image center and dimension
00188           double sizeX = cam.width;
00189           double sizeY = cam.height;
00190           double cx = (sizeX) / 2.0;
00191           double cy = (sizeY) / 2.0;
00192 
00193           double focal_x = cam.focal_length;
00194           double focal_y = cam.focal_length;
00195 
00196           // project point on image frame
00197           UV_coordinates[0] = static_cast<float> ((focal_x * (pt.x / pt.z) + cx) / sizeX); //horizontal
00198           UV_coordinates[1] = 1.0f - static_cast<float> (((focal_y * (pt.y / pt.z) + cy) / sizeY)); //vertical
00199 
00200           // point is visible!
00201           if (UV_coordinates[0] >= 0.0 && UV_coordinates[0] <= 1.0 && UV_coordinates[1] >= 0.0 && UV_coordinates[1]
00202                                                                                                                  <= 1.0)
00203             return (true);
00204         }
00205 
00206         // point is NOT visible by the camera
00207         UV_coordinates[0] = -1.0;
00208         UV_coordinates[1] = -1.0;
00209         return (false);
00210       }
00211 
00217       inline bool
00218       isPointOccluded (const pcl::PointXYZ &pt, const OctreePtr octree);
00219 
00227       void
00228       removeOccludedPoints (const PointCloudPtr &input_cloud,
00229                             PointCloudPtr &filtered_cloud, const double octree_voxel_size,
00230                             std::vector<int> &visible_indices, std::vector<int> &occluded_indices);
00231 
00237       void
00238       removeOccludedPoints (const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh, const double octree_voxel_size);
00239 
00240 
00246       void
00247       removeOccludedPoints (const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud, const double octree_voxel_size);
00248 
00249 
00258       int
00259       sortFacesByCamera (pcl::TextureMesh &tex_mesh, 
00260                          pcl::TextureMesh &sorted_mesh, 
00261                          const pcl::texture_mapping::CameraVector &cameras,
00262                          const double octree_voxel_size, PointCloud &visible_pts);
00263 
00274       void
00275       showOcclusions (const PointCloudPtr &input_cloud, 
00276                       pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
00277                       const double octree_voxel_size, 
00278                       const bool show_nb_occlusions = true,
00279                       const int max_occlusions = 4);
00280 
00291       void
00292       showOcclusions (pcl::TextureMesh &tex_mesh, 
00293                       pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
00294                       double octree_voxel_size, 
00295                       bool show_nb_occlusions = true, 
00296                       int max_occlusions = 4);
00297 
00304       void 
00305       textureMeshwithMultipleCameras (pcl::TextureMesh &mesh, 
00306                                       const pcl::texture_mapping::CameraVector &cameras);
00307 
00308     protected:
00310       float f_;
00311 
00313       Eigen::Vector3f vector_field_;
00314 
00316       std::vector<std::string> tex_files_;
00317 
00319       TexMaterial tex_material_;
00320 
00326       std::vector<Eigen::Vector2f>
00327       mapTexture2Face (const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3);
00328 
00337       inline void
00338       getTriangleCircumcenterAndSize (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circomcenter, double &radius);
00339  
00340       
00349       inline void 
00350       getTriangleCircumcscribedCircleCentroid ( const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circumcenter, double &radius);
00351  
00352 
00359       inline bool
00360       getPointUVCoordinates (const pcl::PointXYZ &pt, const Camera &cam, pcl::PointXY &UV_coordinates);
00361 
00371       inline bool
00372       isFaceProjected (const Camera &camera, 
00373                        const pcl::PointXYZ &p1, const pcl::PointXYZ &p2, const pcl::PointXYZ &p3, 
00374                        pcl::PointXY &proj1, pcl::PointXY &proj2, pcl::PointXY &proj3);
00375 
00383       inline bool
00384       checkPointInsideTriangle (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, const pcl::PointXY &pt);
00385 
00387       std::string
00388       getClassName () const
00389       {
00390         return ("TextureMapping");
00391       }
00392 
00393     public:
00394       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00395   };
00396 }
00397 
00398 #endif /* TEXTURE_MAPPING_H_ */
00399 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:36:33