texture_mapping.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: texture_mapping.hpp 6064 2012-06-29 17:57:23Z raph $
00035  *
00036  */
00037 
00038 #ifndef PCL_SURFACE_IMPL_TEXTURE_MAPPING_HPP_
00039 #define PCL_SURFACE_IMPL_TEXTURE_MAPPING_HPP_
00040 
00041 #include <pcl/surface/texture_mapping.h>
00042 
00044 template<typename PointInT> std::vector<Eigen::Vector2f>
00045 pcl::TextureMapping<PointInT>::mapTexture2Face (
00046     const Eigen::Vector3f &p1, 
00047     const Eigen::Vector3f &p2, 
00048     const Eigen::Vector3f &p3)
00049 {
00050   std::vector<Eigen::Vector2f> tex_coordinates;
00051   // process for each face
00052   Eigen::Vector3f p1p2 (p2[0] - p1[0], p2[1] - p1[1], p2[2] - p1[2]);
00053   Eigen::Vector3f p1p3 (p3[0] - p1[0], p3[1] - p1[1], p3[2] - p1[2]);
00054   Eigen::Vector3f p2p3 (p3[0] - p2[0], p3[1] - p2[1], p3[2] - p2[2]);
00055 
00056   // Normalize
00057   p1p2 = p1p2 / std::sqrt (p1p2.dot (p1p2));
00058   p1p3 = p1p3 / std::sqrt (p1p3.dot (p1p3));
00059   p2p3 = p2p3 / std::sqrt (p2p3.dot (p2p3));
00060 
00061   // compute vector normal of a face
00062   Eigen::Vector3f f_normal = p1p2.cross (p1p3);
00063   f_normal = f_normal / std::sqrt (f_normal.dot (f_normal));
00064 
00065   // project vector field onto the face: vector v1_projected = v1 - Dot(v1, n) * n;
00066   Eigen::Vector3f f_vector_field = vector_field_ - vector_field_.dot (f_normal) * f_normal;
00067 
00068   // Normalize
00069   f_vector_field = f_vector_field / std::sqrt (f_vector_field.dot (f_vector_field));
00070 
00071   // texture coordinates
00072   Eigen::Vector2f tp1, tp2, tp3;
00073 
00074   double alpha = std::acos (f_vector_field.dot (p1p2));
00075 
00076   // distance between 3 vertices of triangles
00077   double e1 = (p2 - p3).norm () / f_;
00078   double e2 = (p1 - p3).norm () / f_;
00079   double e3 = (p1 - p2).norm () / f_;
00080 
00081   // initialize
00082   tp1[0] = 0.0;
00083   tp1[1] = 0.0;
00084 
00085   tp2[0] = static_cast<float> (e3);
00086   tp2[1] = 0.0;
00087 
00088   // determine texture coordinate tp3;
00089   double cos_p1 = (e2 * e2 + e3 * e3 - e1 * e1) / (2 * e2 * e3);
00090   double sin_p1 = sqrt (1 - (cos_p1 * cos_p1));
00091 
00092   tp3[0] = static_cast<float> (cos_p1 * e2);
00093   tp3[1] = static_cast<float> (sin_p1 * e2);
00094 
00095   // rotating by alpha (angle between V and pp1 & pp2)
00096   Eigen::Vector2f r_tp2, r_tp3;
00097   r_tp2[0] = static_cast<float> (tp2[0] * std::cos (alpha) - tp2[1] * std::sin (alpha));
00098   r_tp2[1] = static_cast<float> (tp2[0] * std::sin (alpha) + tp2[1] * std::cos (alpha));
00099 
00100   r_tp3[0] = static_cast<float> (tp3[0] * std::cos (alpha) - tp3[1] * std::sin (alpha));
00101   r_tp3[1] = static_cast<float> (tp3[0] * std::sin (alpha) + tp3[1] * std::cos (alpha));
00102 
00103   // shifting
00104   tp1[0] = tp1[0];
00105   tp2[0] = r_tp2[0];
00106   tp3[0] = r_tp3[0];
00107   tp1[1] = tp1[1];
00108   tp2[1] = r_tp2[1];
00109   tp3[1] = r_tp3[1];
00110 
00111   float min_x = tp1[0];
00112   float min_y = tp1[1];
00113   if (min_x > tp2[0])
00114     min_x = tp2[0];
00115   if (min_x > tp3[0])
00116     min_x = tp3[0];
00117   if (min_y > tp2[1])
00118     min_y = tp2[1];
00119   if (min_y > tp3[1])
00120     min_y = tp3[1];
00121 
00122   if (min_x < 0)
00123   {
00124     tp1[0] = tp1[0] - min_x;
00125     tp2[0] = tp2[0] - min_x;
00126     tp3[0] = tp3[0] - min_x;
00127   }
00128   if (min_y < 0)
00129   {
00130     tp1[1] = tp1[1] - min_y;
00131     tp2[1] = tp2[1] - min_y;
00132     tp3[1] = tp3[1] - min_y;
00133   }
00134 
00135   tex_coordinates.push_back (tp1);
00136   tex_coordinates.push_back (tp2);
00137   tex_coordinates.push_back (tp3);
00138   return (tex_coordinates);
00139 }
00140 
00142 template<typename PointInT> void
00143 pcl::TextureMapping<PointInT>::mapTexture2Mesh (pcl::TextureMesh &tex_mesh)
00144 {
00145   // mesh information
00146   int nr_points = tex_mesh.cloud.width * tex_mesh.cloud.height;
00147   int point_size = static_cast<int> (tex_mesh.cloud.data.size ()) / nr_points;
00148 
00149   // temporary PointXYZ
00150   float x, y, z;
00151   // temporary face
00152   Eigen::Vector3f facet[3];
00153 
00154   // texture coordinates for each mesh
00155   std::vector<std::vector<Eigen::Vector2f> > texture_map;
00156 
00157   for (size_t m = 0; m < tex_mesh.tex_polygons.size (); ++m)
00158   {
00159     // texture coordinates for each mesh
00160     std::vector<Eigen::Vector2f> texture_map_tmp;
00161 
00162     // processing for each face
00163     for (size_t i = 0; i < tex_mesh.tex_polygons[m].size (); ++i)
00164     {
00165       size_t idx;
00166 
00167       // get facet information
00168       for (size_t j = 0; j < tex_mesh.tex_polygons[m][i].vertices.size (); ++j)
00169       {
00170         idx = tex_mesh.tex_polygons[m][i].vertices[j];
00171         memcpy (&x, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[0].offset], sizeof(float));
00172         memcpy (&y, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[1].offset], sizeof(float));
00173         memcpy (&z, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[2].offset], sizeof(float));
00174         facet[j][0] = x;
00175         facet[j][1] = y;
00176         facet[j][2] = z;
00177       }
00178 
00179       // get texture coordinates of each face
00180       std::vector<Eigen::Vector2f> tex_coordinates = mapTexture2Face (facet[0], facet[1], facet[2]);
00181       for (size_t n = 0; n < tex_coordinates.size (); ++n)
00182         texture_map_tmp.push_back (tex_coordinates[n]);
00183     }// end faces
00184 
00185     // texture materials
00186     std::stringstream tex_name;
00187     tex_name << "material_" << m;
00188     tex_name >> tex_material_.tex_name;
00189     tex_material_.tex_file = tex_files_[m];
00190     tex_mesh.tex_materials.push_back (tex_material_);
00191 
00192     // texture coordinates
00193     tex_mesh.tex_coordinates.push_back (texture_map_tmp);
00194   }// end meshes
00195 }
00196 
00198 template<typename PointInT> void
00199 pcl::TextureMapping<PointInT>::mapTexture2MeshUV (pcl::TextureMesh &tex_mesh)
00200 {
00201   // mesh information
00202   int nr_points = tex_mesh.cloud.width * tex_mesh.cloud.height;
00203   int point_size = static_cast<int> (tex_mesh.cloud.data.size ()) / nr_points;
00204 
00205   float x_lowest = 100000;
00206   float x_highest = 0;
00207   float y_lowest = 100000;
00208   //float y_highest = 0 ;
00209   float z_lowest = 100000;
00210   float z_highest = 0;
00211   float x_, y_, z_;
00212 
00213   for (int i = 0; i < nr_points; ++i)
00214   {
00215     memcpy (&x_, &tex_mesh.cloud.data[i * point_size + tex_mesh.cloud.fields[0].offset], sizeof(float));
00216     memcpy (&y_, &tex_mesh.cloud.data[i * point_size + tex_mesh.cloud.fields[1].offset], sizeof(float));
00217     memcpy (&z_, &tex_mesh.cloud.data[i * point_size + tex_mesh.cloud.fields[2].offset], sizeof(float));
00218     // x
00219     if (x_ <= x_lowest)
00220       x_lowest = x_;
00221     if (x_ > x_lowest)
00222       x_highest = x_;
00223 
00224     // y
00225     if (y_ <= y_lowest)
00226       y_lowest = y_;
00227     //if (y_ > y_lowest) y_highest = y_;
00228 
00229     // z
00230     if (z_ <= z_lowest)
00231       z_lowest = z_;
00232     if (z_ > z_lowest)
00233       z_highest = z_;
00234   }
00235   // x
00236   float x_range = (x_lowest - x_highest) * -1;
00237   float x_offset = 0 - x_lowest;
00238   // x
00239   // float y_range = (y_lowest - y_highest)*-1;
00240   // float y_offset = 0 - y_lowest;
00241   // z
00242   float z_range = (z_lowest - z_highest) * -1;
00243   float z_offset = 0 - z_lowest;
00244 
00245   // texture coordinates for each mesh
00246   std::vector<std::vector<Eigen::Vector2f> > texture_map;
00247 
00248   for (size_t m = 0; m < tex_mesh.tex_polygons.size (); ++m)
00249   {
00250     // texture coordinates for each mesh
00251     std::vector<Eigen::Vector2f> texture_map_tmp;
00252 
00253     // processing for each face
00254     for (size_t i = 0; i < tex_mesh.tex_polygons[m].size (); ++i)
00255     {
00256       size_t idx;
00257       Eigen::Vector2f tmp_VT;
00258       for (size_t j = 0; j < tex_mesh.tex_polygons[m][i].vertices.size (); ++j)
00259       {
00260         idx = tex_mesh.tex_polygons[m][i].vertices[j];
00261         memcpy (&x_, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[0].offset], sizeof(float));
00262         memcpy (&y_, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[1].offset], sizeof(float));
00263         memcpy (&z_, &tex_mesh.cloud.data[idx * point_size + tex_mesh.cloud.fields[2].offset], sizeof(float));
00264 
00265         // calculate uv coordinates
00266         tmp_VT[0] = (x_ + x_offset) / x_range;
00267         tmp_VT[1] = (z_ + z_offset) / z_range;
00268         texture_map_tmp.push_back (tmp_VT);
00269       }
00270     }// end faces
00271 
00272     // texture materials
00273     std::stringstream tex_name;
00274     tex_name << "material_" << m;
00275     tex_name >> tex_material_.tex_name;
00276     tex_material_.tex_file = tex_files_[m];
00277     tex_mesh.tex_materials.push_back (tex_material_);
00278 
00279     // texture coordinates
00280     tex_mesh.tex_coordinates.push_back (texture_map_tmp);
00281   }// end meshes
00282 }
00283 
00285 template<typename PointInT> void
00286 pcl::TextureMapping<PointInT>::mapMultipleTexturesToMeshUV (pcl::TextureMesh &tex_mesh, pcl::texture_mapping::CameraVector &cams)
00287 {
00288 
00289   if (tex_mesh.tex_polygons.size () != cams.size () + 1)
00290   {
00291     PCL_ERROR ("The mesh should be divided into nbCamera+1 sub-meshes.\n");
00292     PCL_ERROR ("You provided %d cameras and a mesh containing %d sub-meshes.\n", cams.size (), tex_mesh.tex_polygons.size ());
00293     return;
00294   }
00295 
00296   PCL_INFO ("You provided %d  cameras and a mesh containing %d sub-meshes.\n", cams.size (), tex_mesh.tex_polygons.size ());
00297 
00298   pcl::PointCloud<pcl::PointXYZ>::Ptr originalCloud (new pcl::PointCloud<pcl::PointXYZ>);
00299   pcl::PointCloud<pcl::PointXYZ>::Ptr camera_transformed_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00300 
00301   // convert mesh's cloud to pcl format for ease
00302   pcl::fromROSMsg (tex_mesh.cloud, *originalCloud);
00303 
00304   // texture coordinates for each mesh
00305   std::vector<std::vector<Eigen::Vector2f> > texture_map;
00306 
00307   for (size_t m = 0; m < cams.size (); ++m)
00308   {
00309     // get current camera parameters
00310     Camera current_cam = cams[m];
00311 
00312     // get camera transform
00313     Eigen::Affine3f cam_trans = current_cam.pose;
00314 
00315     // transform cloud into current camera frame
00316     pcl::transformPointCloud (*originalCloud, *camera_transformed_cloud, cam_trans.inverse ());
00317 
00318     // vector of texture coordinates for each face
00319     std::vector<Eigen::Vector2f> texture_map_tmp;
00320 
00321     // processing each face visible by this camera
00322     pcl::PointXYZ pt;
00323     size_t idx;
00324     for (size_t i = 0; i < tex_mesh.tex_polygons[m].size (); ++i)
00325     {
00326       Eigen::Vector2f tmp_VT;
00327       // for each point of this face
00328       for (size_t j = 0; j < tex_mesh.tex_polygons[m][i].vertices.size (); ++j)
00329       {
00330         // get point
00331         idx = tex_mesh.tex_polygons[m][i].vertices[j];
00332         pt = camera_transformed_cloud->points[idx];
00333 
00334         // compute UV coordinates for this point
00335         getPointUVCoordinates (pt, current_cam, tmp_VT);
00336         texture_map_tmp.push_back (tmp_VT);
00337 
00338       }// end points
00339     }// end faces
00340 
00341     // texture materials
00342     std::stringstream tex_name;
00343     tex_name << "material_" << m;
00344     tex_name >> tex_material_.tex_name;
00345     tex_material_.tex_file = current_cam.texture_file;
00346     tex_mesh.tex_materials.push_back (tex_material_);
00347 
00348     // texture coordinates
00349     tex_mesh.tex_coordinates.push_back (texture_map_tmp);
00350   }// end cameras
00351 
00352   // push on extra empty UV map (for unseen faces) so that obj writer does not crash!
00353   std::vector<Eigen::Vector2f> texture_map_tmp;
00354   for (size_t i = 0; i < tex_mesh.tex_polygons[cams.size ()].size (); ++i)
00355     for (size_t j = 0; j < tex_mesh.tex_polygons[cams.size ()][i].vertices.size (); ++j)
00356     {
00357       Eigen::Vector2f tmp_VT;
00358       tmp_VT[0] = -1;
00359       tmp_VT[1] = -1;
00360       texture_map_tmp.push_back (tmp_VT);
00361     }
00362 
00363   tex_mesh.tex_coordinates.push_back (texture_map_tmp);
00364 
00365   // push on an extra dummy material for the same reason
00366   std::stringstream tex_name;
00367   tex_name << "material_" << cams.size ();
00368   tex_name >> tex_material_.tex_name;
00369   tex_material_.tex_file = "occluded.jpg";
00370   tex_mesh.tex_materials.push_back (tex_material_);
00371 
00372 }
00373 
00375 template<typename PointInT> bool
00376 pcl::TextureMapping<PointInT>::isPointOccluded (const pcl::PointXYZ &pt, OctreePtr octree)
00377 {
00378   Eigen::Vector3f direction;
00379   direction (0) = pt.x;
00380   direction (1) = pt.y;
00381   direction (2) = pt.z;
00382 
00383   std::vector<int> indices;
00384 
00385   PointCloudConstPtr cloud (new PointCloud());
00386   cloud = octree->getInputCloud();
00387 
00388   double distance_threshold = octree->getResolution();
00389 
00390   // raytrace
00391   octree->getIntersectedVoxelIndices(direction, -direction, indices);
00392 
00393   int nbocc = static_cast<int> (indices.size ());
00394   for (size_t j = 0; j < indices.size (); j++)
00395   {
00396    // if intersected point is on the over side of the camera
00397    if (pt.z * cloud->points[indices[j]].z < 0)
00398    {
00399      nbocc--;
00400      continue;
00401    }
00402 
00403    if (fabs (cloud->points[indices[j]].z - pt.z) <= distance_threshold)
00404    {
00405      // points are very close to each-other, we do not consider the occlusion
00406      nbocc--;
00407    }
00408   }
00409 
00410   if (nbocc == 0)
00411    return (false);
00412   else
00413    return (true);
00414 }
00415 
00417 template<typename PointInT> void
00418 pcl::TextureMapping<PointInT>::removeOccludedPoints (const PointCloudPtr &input_cloud,
00419                                                      PointCloudPtr &filtered_cloud,
00420                                                      const double octree_voxel_size, std::vector<int> &visible_indices,
00421                                                      std::vector<int> &occluded_indices)
00422 {
00423   // variable used to filter occluded points by depth
00424   double maxDeltaZ = octree_voxel_size;
00425 
00426   // create an octree to perform rayTracing
00427   OctreePtr octree (new Octree (octree_voxel_size));
00428   // create octree structure
00429   octree->setInputCloud (input_cloud);
00430   // update bounding box automatically
00431   octree->defineBoundingBox ();
00432   // add points in the tree
00433   octree->addPointsFromInputCloud ();
00434 
00435   visible_indices.clear ();
00436 
00437   // for each point of the cloud, raycast toward camera and check intersected voxels.
00438   Eigen::Vector3f direction;
00439   std::vector<int> indices;
00440   for (size_t i = 0; i < input_cloud->points.size (); ++i)
00441   {
00442     direction (0) = input_cloud->points[i].x;
00443     direction (1) = input_cloud->points[i].y;
00444     direction (2) = input_cloud->points[i].z;
00445 
00446     // if point is not occluded
00447     octree->getIntersectedVoxelIndices (direction, -direction, indices);
00448 
00449     int nbocc = static_cast<int> (indices.size ());
00450     for (size_t j = 0; j < indices.size (); j++)
00451     {
00452       // if intersected point is on the over side of the camera
00453       if (input_cloud->points[i].z * input_cloud->points[indices[j]].z < 0)
00454       {
00455         nbocc--;
00456         continue;
00457       }
00458 
00459       if (fabs (input_cloud->points[indices[j]].z - input_cloud->points[i].z) <= maxDeltaZ)
00460       {
00461         // points are very close to each-other, we do not consider the occlusion
00462         nbocc--;
00463       }
00464     }
00465 
00466     if (nbocc == 0)
00467     {
00468       // point is added in the filtered mesh
00469       filtered_cloud->points.push_back (input_cloud->points[i]);
00470       visible_indices.push_back (static_cast<int> (i));
00471     }
00472     else
00473     {
00474       occluded_indices.push_back (static_cast<int> (i));
00475     }
00476   }
00477 
00478 }
00479 
00481 template<typename PointInT> void
00482 pcl::TextureMapping<PointInT>::removeOccludedPoints (const pcl::TextureMesh &tex_mesh, pcl::TextureMesh &cleaned_mesh, const double octree_voxel_size)
00483 {
00484   // copy mesh
00485   cleaned_mesh = tex_mesh;
00486 
00487   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00488   pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00489 
00490   // load points into a PCL format
00491   pcl::fromROSMsg (tex_mesh.cloud, *cloud);
00492 
00493   std::vector<int> visible, occluded;
00494   removeOccludedPoints (cloud, filtered_cloud, octree_voxel_size, visible, occluded);
00495 
00496   // Now that we know which points are visible, let's iterate over each face.
00497   // if the face has one invisible point => out!
00498   for (size_t polygons = 0; polygons < cleaned_mesh.tex_polygons.size (); ++polygons)
00499   {
00500     // remove all faces from cleaned mesh
00501     cleaned_mesh.tex_polygons[polygons].clear ();
00502     // iterate over faces
00503     for (size_t faces = 0; faces < tex_mesh.tex_polygons[polygons].size (); ++faces)
00504     {
00505       // check if all the face's points are visible
00506       bool faceIsVisible = true;
00507       std::vector<int>::iterator it;
00508 
00509       // iterate over face's vertex
00510       for (size_t points = 0; points < tex_mesh.tex_polygons[polygons][faces].vertices.size (); ++points)
00511       {
00512         it = find (occluded.begin (), occluded.end (), tex_mesh.tex_polygons[polygons][faces].vertices[points]);
00513 
00514         if (it == occluded.end ())
00515         {
00516           // point is not in the occluded vector
00517           // PCL_INFO ("  VISIBLE!\n");
00518         }
00519         else
00520         {
00521           // point was occluded
00522           // PCL_INFO("  OCCLUDED!\n");
00523           faceIsVisible = false;
00524         }
00525       }
00526 
00527       if (faceIsVisible)
00528       {
00529         cleaned_mesh.tex_polygons[polygons].push_back (tex_mesh.tex_polygons[polygons][faces]);
00530       }
00531 
00532     }
00533   }
00534 }
00535 
00537 template<typename PointInT> void
00538 pcl::TextureMapping<PointInT>::removeOccludedPoints (const pcl::TextureMesh &tex_mesh, PointCloudPtr &filtered_cloud,
00539                       const double octree_voxel_size)
00540 {
00541   PointCloudPtr cloud (new PointCloud);
00542 
00543   // load points into a PCL format
00544   pcl::fromROSMsg (tex_mesh.cloud, *cloud);
00545 
00546   std::vector<int> visible, occluded;
00547   removeOccludedPoints (cloud, filtered_cloud, octree_voxel_size, visible, occluded);
00548 
00549 }
00550 
00552 template<typename PointInT> int
00553 pcl::TextureMapping<PointInT>::sortFacesByCamera (pcl::TextureMesh &tex_mesh, pcl::TextureMesh &sorted_mesh,
00554                                                   const pcl::texture_mapping::CameraVector &cameras, const double octree_voxel_size,
00555                                                   PointCloud &visible_pts)
00556 {
00557   if (tex_mesh.tex_polygons.size () != 1)
00558   {
00559     PCL_ERROR ("The mesh must contain only 1 sub-mesh!\n");
00560     return (-1);
00561   }
00562 
00563   if (cameras.size () == 0)
00564   {
00565     PCL_ERROR ("Must provide at least one camera info!\n");
00566     return (-1);
00567   }
00568 
00569   // copy mesh
00570   sorted_mesh = tex_mesh;
00571   // clear polygons from cleaned_mesh
00572   sorted_mesh.tex_polygons.clear ();
00573 
00574   pcl::PointCloud<pcl::PointXYZ>::Ptr original_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00575   pcl::PointCloud<pcl::PointXYZ>::Ptr transformed_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00576   pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00577 
00578   // load points into a PCL format
00579   pcl::fromROSMsg (tex_mesh.cloud, *original_cloud);
00580 
00581   // for each camera
00582   for (size_t cam = 0; cam < cameras.size (); ++cam)
00583   {
00584     // get camera pose as transform
00585     Eigen::Affine3f cam_trans = cameras[cam].pose;
00586 
00587     // transform original cloud in camera coordinates
00588     pcl::transformPointCloud (*original_cloud, *transformed_cloud, cam_trans.inverse ());
00589 
00590     // find occlusions on transformed cloud
00591     std::vector<int> visible, occluded;
00592     removeOccludedPoints (transformed_cloud, filtered_cloud, octree_voxel_size, visible, occluded);
00593     visible_pts = *filtered_cloud;
00594 
00595     // find visible faces => add them to polygon N for camera N
00596     // add polygon group for current camera in clean
00597     std::vector<pcl::Vertices> visibleFaces_currentCam;
00598     // iterate over the faces of the current mesh
00599     for (size_t faces = 0; faces < tex_mesh.tex_polygons[0].size (); ++faces)
00600     {
00601       // check if all the face's points are visible
00602       bool faceIsVisible = true;
00603       std::vector<int>::iterator it;
00604 
00605       // iterate over face's vertex
00606       for (size_t current_pt_indice = 0; faceIsVisible && current_pt_indice < tex_mesh.tex_polygons[0][faces].vertices.size (); ++current_pt_indice)
00607       {
00608         // TODO this is far too long! Better create an helper function that raycasts here.
00609         it = find (occluded.begin (), occluded.end (), tex_mesh.tex_polygons[0][faces].vertices[current_pt_indice]);
00610 
00611         if (it == occluded.end ())
00612         {
00613           // point is not occluded
00614           // does it land on the camera's image plane?
00615           pcl::PointXYZ pt = transformed_cloud->points[tex_mesh.tex_polygons[0][faces].vertices[current_pt_indice]];
00616           Eigen::Vector2f dummy_UV;
00617           if (!getPointUVCoordinates (pt, cameras[cam], dummy_UV))
00618           {
00619             // point is not visible by the camera
00620             faceIsVisible = false;
00621           }
00622         }
00623         else
00624         {
00625           faceIsVisible = false;
00626         }
00627       }
00628 
00629       if (faceIsVisible)
00630       {
00631         // push current visible face into the sorted mesh
00632         visibleFaces_currentCam.push_back (tex_mesh.tex_polygons[0][faces]);
00633         // remove it from the unsorted mesh
00634         tex_mesh.tex_polygons[0].erase (tex_mesh.tex_polygons[0].begin () + faces);
00635         faces--;
00636       }
00637 
00638     }
00639     sorted_mesh.tex_polygons.push_back (visibleFaces_currentCam);
00640   }
00641 
00642   // we should only have occluded and non-visible faces left in tex_mesh.tex_polygons[0]
00643   // we need to add them as an extra polygon in the sorted mesh
00644   sorted_mesh.tex_polygons.push_back (tex_mesh.tex_polygons[0]);
00645   return (0);
00646 }
00647 
00649 template<typename PointInT> void
00650 pcl::TextureMapping<PointInT>::showOcclusions (const PointCloudPtr &input_cloud,
00651                                                pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
00652                                                const double octree_voxel_size, const bool show_nb_occlusions,
00653                                                const int max_occlusions)
00654                                                {
00655   // variable used to filter occluded points by depth
00656   double maxDeltaZ = octree_voxel_size * 2.0;
00657 
00658   // create an octree to perform rayTracing
00659   pcl::octree::OctreePointCloudSearch<PointInT> *octree;
00660   octree = new pcl::octree::OctreePointCloudSearch<PointInT> (octree_voxel_size);
00661   // create octree structure
00662   octree->setInputCloud (input_cloud);
00663   // update bounding box automatically
00664   octree->defineBoundingBox ();
00665   // add points in the tree
00666   octree->addPointsFromInputCloud ();
00667 
00668   // ray direction
00669   Eigen::Vector3f direction;
00670 
00671   std::vector<int> indices;
00672   // point from where we ray-trace
00673   pcl::PointXYZI pt;
00674 
00675   std::vector<double> zDist;
00676   std::vector<double> ptDist;
00677   // for each point of the cloud, ray-trace toward the camera and check intersected voxels.
00678   for (size_t i = 0; i < input_cloud->points.size (); ++i)
00679   {
00680     direction (0) = input_cloud->points[i].x;
00681     pt.x = input_cloud->points[i].x;
00682     direction (1) = input_cloud->points[i].y;
00683     pt.y = input_cloud->points[i].y;
00684     direction (2) = input_cloud->points[i].z;
00685     pt.z = input_cloud->points[i].z;
00686 
00687     // get number of occlusions for that point
00688     indices.clear ();
00689     int nbocc = octree->getIntersectedVoxelIndices (direction, -direction, indices);
00690 
00691     nbocc = static_cast<int> (indices.size ());
00692 
00693     // TODO need to clean this up and find tricks to get remove aliasaing effect on planes
00694     for (size_t j = 0; j < indices.size (); j++)
00695     {
00696       // if intersected point is on the over side of the camera
00697       if (pt.z * input_cloud->points[indices[j]].z < 0)
00698       {
00699         nbocc--;
00700       }
00701       else if (fabs (input_cloud->points[indices[j]].z - pt.z) <= maxDeltaZ)
00702       {
00703         // points are very close to each-other, we do not consider the occlusion
00704         nbocc--;
00705       }
00706       else
00707       {
00708         zDist.push_back (fabs (input_cloud->points[indices[j]].z - pt.z));
00709         ptDist.push_back (pcl::euclideanDistance (input_cloud->points[indices[j]], pt));
00710       }
00711     }
00712 
00713     if (show_nb_occlusions)
00714       (nbocc <= max_occlusions) ? (pt.intensity = static_cast<float> (nbocc)) : (pt.intensity = static_cast<float> (max_occlusions));
00715     else
00716       (nbocc == 0) ? (pt.intensity = 0) : (pt.intensity = 1);
00717 
00718     colored_cloud->points.push_back (pt);
00719   }
00720 
00721   if (zDist.size () >= 2)
00722   {
00723     std::sort (zDist.begin (), zDist.end ());
00724     std::sort (ptDist.begin (), ptDist.end ());
00725   }
00726 }
00727 
00729 template<typename PointInT> void
00730 pcl::TextureMapping<PointInT>::showOcclusions (pcl::TextureMesh &tex_mesh, pcl::PointCloud<pcl::PointXYZI>::Ptr &colored_cloud,
00731                   double octree_voxel_size, bool show_nb_occlusions, int max_occlusions)
00732 {
00733   // load points into a PCL format
00734   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00735   pcl::fromROSMsg (tex_mesh.cloud, *cloud);
00736 
00737   showOcclusions (cloud, colored_cloud, octree_voxel_size, show_nb_occlusions, max_occlusions);
00738 }
00739 
00741 template<typename PointInT> void
00742 pcl::TextureMapping<PointInT>::textureMeshwithMultipleCameras (pcl::TextureMesh &mesh, const pcl::texture_mapping::CameraVector &cameras)
00743 {
00744 
00745   if (mesh.tex_polygons.size () != 1)
00746     return;
00747 
00748   pcl::PointCloud<pcl::PointXYZ>::Ptr mesh_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00749 
00750   pcl::fromROSMsg (mesh.cloud, *mesh_cloud);
00751 
00752   std::vector<pcl::Vertices> faces;
00753 
00754   for (int current_cam = 0; current_cam < static_cast<int> (cameras.size ()); ++current_cam)
00755   {
00756     PCL_INFO ("Processing camera %d of %d.\n", current_cam+1, cameras.size ());
00757     
00758     // transform mesh into camera's frame
00759     pcl::PointCloud<pcl::PointXYZ>::Ptr camera_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00760     pcl::transformPointCloud (*mesh_cloud, *camera_cloud, cameras[current_cam].pose.inverse ());
00761 
00762     // CREATE UV MAP FOR CURRENT FACES
00763     pcl::PointCloud<pcl::PointXY>::Ptr projections (new pcl::PointCloud<pcl::PointXY>);
00764     std::vector<pcl::Vertices>::iterator current_face;
00765     std::vector<bool> visibility;
00766     visibility.resize (mesh.tex_polygons[current_cam].size ());
00767     std::vector<UvIndex> indexes_uv_to_points;
00768     // for each current face
00769 
00770     //TODO change this
00771     pcl::PointXY nan_point;
00772     nan_point.x = std::numeric_limits<float>::quiet_NaN ();
00773     nan_point.y = std::numeric_limits<float>::quiet_NaN ();
00774     UvIndex u_null;
00775     u_null.idx_cloud = -1;
00776     u_null.idx_face = -1;
00777 
00778     int cpt_invisible=0;
00779     for (int idx_face = 0; idx_face <  static_cast<int> (mesh.tex_polygons[current_cam].size ()); ++idx_face)
00780     {
00781       //project each vertice, if one is out of view, stop
00782       pcl::PointXY uv_coord1;
00783       pcl::PointXY uv_coord2;
00784       pcl::PointXY uv_coord3;
00785 
00786       if (isFaceProjected (cameras[current_cam],
00787                            camera_cloud->points[mesh.tex_polygons[current_cam][idx_face].vertices[0]],
00788                            camera_cloud->points[mesh.tex_polygons[current_cam][idx_face].vertices[1]],
00789                            camera_cloud->points[mesh.tex_polygons[current_cam][idx_face].vertices[2]],
00790                            uv_coord1,
00791                            uv_coord2,
00792                            uv_coord3))
00793        {
00794         // face is in the camera's FOV
00795 
00796         // add UV coordinates
00797         projections->points.push_back (uv_coord1);
00798         projections->points.push_back (uv_coord2);
00799         projections->points.push_back (uv_coord3);
00800 
00801         // remember corresponding face
00802         UvIndex u1, u2, u3;
00803         u1.idx_cloud = mesh.tex_polygons[current_cam][idx_face].vertices[0];
00804         u2.idx_cloud = mesh.tex_polygons[current_cam][idx_face].vertices[1];
00805         u3.idx_cloud = mesh.tex_polygons[current_cam][idx_face].vertices[2];
00806         u1.idx_face = idx_face; u2.idx_face = idx_face; u3.idx_face = idx_face;
00807         indexes_uv_to_points.push_back (u1);
00808         indexes_uv_to_points.push_back (u2);
00809         indexes_uv_to_points.push_back (u3);
00810 
00811         //keep track of visibility
00812         visibility[idx_face] = true;
00813       }
00814       else
00815       {
00816         projections->points.push_back (nan_point);
00817         projections->points.push_back (nan_point);
00818         projections->points.push_back (nan_point);
00819         indexes_uv_to_points.push_back (u_null);
00820         indexes_uv_to_points.push_back (u_null);
00821         indexes_uv_to_points.push_back (u_null);
00822         //keep track of visibility
00823         visibility[idx_face] = false;
00824         cpt_invisible++;
00825       }
00826     }
00827 
00828     // projections contains all UV points of the current faces
00829     // indexes_uv_to_points links a uv point to its point in the camera cloud
00830     // visibility contains tells if a face was in the camera FOV (false = skip)
00831 
00832     // TODO handle case were no face could be projected
00833     if (visibility.size () - cpt_invisible !=0)
00834     {
00835         //create kdtree
00836         pcl::KdTreeFLANN<pcl::PointXY> kdtree;
00837         kdtree.setInputCloud (projections);
00838 
00839         std::vector<int> idxNeighbors;
00840         std::vector<float> neighborsSquaredDistance;
00841         // af first (idx_pcan < current_cam), check if some of the faces attached to previous cameras occlude the current faces
00842         // then (idx_pcam == current_cam), check for self occlusions. At this stage, we skip faces that were already marked as occluded
00843         cpt_invisible = 0;
00844         for (int idx_pcam = 0 ; idx_pcam <= current_cam ; ++idx_pcam)
00845         {
00846           // project all faces
00847           for (int idx_face = 0; idx_face <  static_cast<int> (mesh.tex_polygons[idx_pcam].size ()); ++idx_face)
00848           {
00849 
00850             if (idx_pcam == current_cam && !visibility[idx_face])
00851             {
00852               // we are now checking for self occlusions within the current faces
00853               // the current face was already declared as occluded.
00854               // therefore, it cannot occlude another face anymore => we skip it
00855               continue;
00856             }
00857 
00858             // project each vertice, if one is out of view, stop
00859             pcl::PointXY uv_coord1;
00860             pcl::PointXY uv_coord2;
00861             pcl::PointXY uv_coord3;
00862 
00863             if (isFaceProjected (cameras[current_cam],
00864                                  camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[0]],
00865                                  camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[1]],
00866                                  camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[2]],
00867                                  uv_coord1,
00868                                  uv_coord2,
00869                                  uv_coord3))
00870              {
00871               // face is in the camera's FOV
00872               //get its circumsribed circle
00873               double radius;
00874               pcl::PointXY center;
00875               getTriangleCircumcenterAndSize (uv_coord1, uv_coord2, uv_coord3, center, radius);
00876 
00877               // get points inside circ.circle
00878               if (kdtree.radiusSearch (center, radius, idxNeighbors, neighborsSquaredDistance) > 0 )
00879               {
00880                 // for each neighbor
00881                 for (size_t i = 0; i < idxNeighbors.size (); ++i)
00882                 {
00883                   if (std::max (camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[0]].z,
00884                                 std::max (camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[1]].z, 
00885                                           camera_cloud->points[mesh.tex_polygons[idx_pcam][idx_face].vertices[2]].z))
00886                      < camera_cloud->points[indexes_uv_to_points[idxNeighbors[i]].idx_cloud].z)
00887                   {
00888                     // neighbor is farther than all the face's points. Check if it falls into the triangle
00889                     if (checkPointInsideTriangle(uv_coord1, uv_coord2, uv_coord3, projections->points[idxNeighbors[i]]))
00890                     {
00891                       // current neighbor is inside triangle and is closer => the corresponding face
00892                       visibility[indexes_uv_to_points[idxNeighbors[i]].idx_face] = false;
00893                       cpt_invisible++;
00894                       //TODO we could remove the projections of this face from the kd-tree cloud, but I fond it slower, and I need the point to keep ordered to querry UV coordinates later
00895                     }
00896                   }
00897                 }
00898               }
00899              }
00900           }
00901         }
00902     }
00903 
00904     // now, visibility is true for each face that belongs to the current camera
00905     // if a face is not visible, we push it into the next one.
00906 
00907     if (static_cast<int> (mesh.tex_coordinates.size ()) <= current_cam)
00908     {
00909       std::vector<Eigen::Vector2f> dummy_container;
00910       mesh.tex_coordinates.push_back (dummy_container);
00911     }
00912     mesh.tex_coordinates[current_cam].resize (3 * visibility.size ());
00913 
00914     std::vector<pcl::Vertices> occluded_faces;
00915     occluded_faces.resize (visibility.size ());
00916     std::vector<pcl::Vertices> visible_faces;
00917     visible_faces.resize (visibility.size ());
00918 
00919     int cpt_occluded_faces = 0;
00920     int cpt_visible_faces = 0;
00921 
00922     for (size_t idx_face = 0 ; idx_face < visibility.size () ; ++idx_face)
00923     {
00924       if (visibility[idx_face])
00925       {
00926         // face is visible by the current camera copy UV coordinates
00927         mesh.tex_coordinates[current_cam][cpt_visible_faces * 3](0) = projections->points[idx_face*3].x;
00928         mesh.tex_coordinates[current_cam][cpt_visible_faces * 3](1) = projections->points[idx_face*3].y;
00929 
00930         mesh.tex_coordinates[current_cam][cpt_visible_faces * 3 + 1](0) = projections->points[idx_face*3 + 1].x;
00931         mesh.tex_coordinates[current_cam][cpt_visible_faces * 3 + 1](1) = projections->points[idx_face*3 + 1].y;
00932 
00933         mesh.tex_coordinates[current_cam][cpt_visible_faces * 3 + 2](0) = projections->points[idx_face*3 + 2].x;
00934         mesh.tex_coordinates[current_cam][cpt_visible_faces * 3 + 2](1) = projections->points[idx_face*3 + 2].y;
00935 
00936         visible_faces[cpt_visible_faces] = mesh.tex_polygons[current_cam][idx_face];
00937 
00938         cpt_visible_faces++;
00939       }
00940       else
00941       {
00942         // face is occluded copy face into temp vector
00943         occluded_faces[cpt_occluded_faces] = mesh.tex_polygons[current_cam][idx_face];
00944         cpt_occluded_faces++;
00945       }
00946     }
00947     mesh.tex_coordinates[current_cam].resize (cpt_visible_faces*3);
00948 
00949     occluded_faces.resize (cpt_occluded_faces);
00950     mesh.tex_polygons.push_back (occluded_faces);
00951 
00952     visible_faces.resize (cpt_visible_faces);
00953     mesh.tex_polygons[current_cam].clear ();
00954     mesh.tex_polygons[current_cam] = visible_faces;
00955 
00956     int nb_faces = 0;
00957     for (int i = 0; i < static_cast<int> (mesh.tex_polygons.size ()); i++)
00958       nb_faces += static_cast<int> (mesh.tex_polygons[i].size ());
00959   }
00960 
00961   // we have been through all the cameras.
00962   // if any faces are left, they were not visible by any camera
00963   // we still need to produce uv coordinates for them
00964 
00965   if (mesh.tex_coordinates.size() <= cameras.size ())
00966   {
00967    std::vector<Eigen::Vector2f> dummy_container;
00968    mesh.tex_coordinates.push_back(dummy_container);
00969    }
00970 
00971 
00972   for(size_t idx_face = 0 ; idx_face < mesh.tex_polygons[cameras.size()].size() ; ++idx_face)
00973   {
00974     Eigen::Vector2f UV1, UV2, UV3;
00975     UV1(0) = -1.0; UV1(1) = -1.0;
00976     UV2(0) = -1.0; UV2(1) = -1.0;
00977     UV3(0) = -1.0; UV3(1) = -1.0;
00978     mesh.tex_coordinates[cameras.size()].push_back(UV1);
00979     mesh.tex_coordinates[cameras.size()].push_back(UV2);
00980     mesh.tex_coordinates[cameras.size()].push_back(UV3);
00981   }
00982 
00983 }
00984 
00986 template<typename PointInT> inline void
00987 pcl::TextureMapping<PointInT>::getTriangleCircumcenterAndSize(const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, pcl::PointXY &circomcenter, double &radius)
00988 {
00989   // we simplify the problem by translating the triangle's origin to its first point
00990   pcl::PointXY ptB, ptC;
00991   ptB.x = p2.x - p1.x; ptB.y = p2.y - p1.y; // B'=B-A
00992   ptC.x = p3.x - p1.x; ptC.y = p3.y - p1.y; // C'=C-A
00993 
00994   double D = 2.0*(ptB.x*ptC.y - ptB.y*ptC.x); // D'=2(B'x*C'y - B'y*C'x)
00995 
00996   // Safety check to avoid division by zero
00997   if(D == 0)
00998   {
00999     circomcenter.x = p1.x;
01000     circomcenter.y = p1.y;
01001   }
01002   else
01003   {
01004     // compute squares once
01005     double bx2 = ptB.x * ptB.x; // B'x^2
01006     double by2 = ptB.y * ptB.y; // B'y^2
01007     double cx2 = ptC.x * ptC.x; // C'x^2
01008     double cy2 = ptC.y * ptC.y; // C'y^2
01009 
01010     // compute circomcenter's coordinates (translate back to original coordinates)
01011     circomcenter.x = static_cast<float> (p1.x + (ptC.y*(bx2 + by2) - ptB.y*(cx2 + cy2)) / D);
01012     circomcenter.y = static_cast<float> (p1.y + (ptB.x*(cx2 + cy2) - ptC.x*(bx2 + by2)) / D);
01013   }
01014 
01015   radius = sqrt( (circomcenter.x - p1.x)*(circomcenter.x - p1.x)  + (circomcenter.y - p1.y)*(circomcenter.y - p1.y));//2.0* (p1.x*(p2.y - p3.y)  + p2.x*(p3.y - p1.y) + p3.x*(p1.y - p2.y));
01016 }
01017 
01019 template<typename PointInT> inline bool
01020 pcl::TextureMapping<PointInT>::getPointUVCoordinates(const pcl::PointXYZ &pt, const Camera &cam, pcl::PointXY &UV_coordinates)
01021 {
01022   if (pt.z > 0)
01023   {
01024     // compute image center and dimension
01025     double sizeX = cam.width;
01026     double sizeY = cam.height;
01027     double cx = sizeX / 2.0;
01028     double cy = sizeY / 2.0;
01029 
01030     // project point on camera's image plane
01031     UV_coordinates.x = static_cast<float> ((cam.focal_length * (pt.x / pt.z) + cx) / sizeX); //horizontal
01032     UV_coordinates.y = 1.0f - static_cast<float> ((cam.focal_length * (pt.y / pt.z) + cy) / sizeY); //vertical
01033 
01034     // point is visible!
01035     if (UV_coordinates.x >= 0.0 && UV_coordinates.x <= 1.0 && UV_coordinates.y >= 0.0 && UV_coordinates.y <= 1.0)
01036       return (true); // point was visible by the camera
01037   }
01038 
01039   // point is NOT visible by the camera
01040   UV_coordinates.x = -1.0f;
01041   UV_coordinates.y = -1.0f;
01042   return (false); // point was not visible by the camera
01043 }
01044 
01046 template<typename PointInT> inline bool
01047 pcl::TextureMapping<PointInT>::checkPointInsideTriangle(const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, const pcl::PointXY &pt)
01048 {
01049    // Compute vectors
01050    Eigen::Vector2d v0, v1, v2;
01051    v0(0) = p3.x - p1.x; v0(1) = p3.y - p1.y; // v0= C - A
01052    v1(0) = p2.x - p1.x; v1(1) = p2.y - p1.y; // v1= B - A
01053    v2(0) = pt.x - p1.x; v2(1) = pt.y - p1.y; // v2= P - A
01054 
01055    // Compute dot products
01056    double dot00 = v0.dot(v0); // dot00 = dot(v0, v0)
01057    double dot01 = v0.dot(v1); // dot01 = dot(v0, v1)
01058    double dot02 = v0.dot(v2); // dot02 = dot(v0, v2)
01059    double dot11 = v1.dot(v1); // dot11 = dot(v1, v1)
01060    double dot12 = v1.dot(v2); // dot12 = dot(v1, v2)
01061 
01062    // Compute barycentric coordinates
01063    double invDenom = 1.0 / (dot00*dot11 - dot01*dot01);
01064    double u = (dot11*dot02 - dot01*dot12) * invDenom;
01065    double v = (dot00*dot12 - dot01*dot02) * invDenom;
01066 
01067    // Check if point is in triangle
01068    return ((u >= 0) && (v >= 0) && (u + v < 1));
01069 }
01070 
01072 template<typename PointInT> inline bool
01073 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)
01074 {
01075   return (getPointUVCoordinates(p1, camera, proj1)
01076       &&
01077       getPointUVCoordinates(p2, camera, proj2)
01078       &&
01079       getPointUVCoordinates(p3, camera, proj3)
01080   );
01081 }
01082 
01083 #define PCL_INSTANTIATE_TextureMapping(T)                \
01084     template class PCL_EXPORTS pcl::TextureMapping<T>;
01085 
01086 #endif /* TEXTURE_MAPPING_HPP_ */
01087 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:47