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_RECONSTRUCTION_IMPL_H_ 00041 #define PCL_SURFACE_RECONSTRUCTION_IMPL_H_ 00042 #include <pcl/search/pcl_search.h> 00043 00045 template <typename PointInT> void 00046 pcl::SurfaceReconstruction<PointInT>::reconstruct (pcl::PolygonMesh &output) 00047 { 00048 // Copy the header 00049 output.header = input_->header; 00050 00051 if (!initCompute ()) 00052 { 00053 output.cloud.width = output.cloud.height = 0; 00054 output.cloud.data.clear (); 00055 output.polygons.clear (); 00056 return; 00057 } 00058 00059 // Check if a space search locator was given 00060 if (check_tree_) 00061 { 00062 if (!tree_) 00063 { 00064 if (input_->isOrganized ()) 00065 tree_.reset (new pcl::search::OrganizedNeighbor<PointInT> ()); 00066 else 00067 tree_.reset (new pcl::search::KdTree<PointInT> (false)); 00068 } 00069 00070 // Send the surface dataset to the spatial locator 00071 tree_->setInputCloud (input_, indices_); 00072 } 00073 00074 // Set up the output dataset 00075 pcl::toPCLPointCloud2 (*input_, output.cloud); 00076 output.polygons.clear (); 00077 output.polygons.reserve (2*indices_->size ()); 00078 // Perform the actual surface reconstruction 00079 performReconstruction (output); 00080 00081 deinitCompute (); 00082 } 00083 00085 template <typename PointInT> void 00086 pcl::SurfaceReconstruction<PointInT>::reconstruct (pcl::PointCloud<PointInT> &points, 00087 std::vector<pcl::Vertices> &polygons) 00088 { 00089 // Copy the header 00090 points.header = input_->header; 00091 00092 if (!initCompute ()) 00093 { 00094 points.width = points.height = 0; 00095 points.clear (); 00096 polygons.clear (); 00097 return; 00098 } 00099 00100 // Check if a space search locator was given 00101 if (check_tree_) 00102 { 00103 if (!tree_) 00104 { 00105 if (input_->isOrganized ()) 00106 tree_.reset (new pcl::search::OrganizedNeighbor<PointInT> ()); 00107 else 00108 tree_.reset (new pcl::search::KdTree<PointInT> (false)); 00109 } 00110 00111 // Send the surface dataset to the spatial locator 00112 tree_->setInputCloud (input_, indices_); 00113 } 00114 00115 // Set up the output dataset 00116 polygons.clear (); 00117 polygons.reserve (2 * indices_->size ()); 00118 // Perform the actual surface reconstruction 00119 performReconstruction (points, polygons); 00120 00121 deinitCompute (); 00122 } 00123 00125 template <typename PointInT> void 00126 pcl::MeshConstruction<PointInT>::reconstruct (pcl::PolygonMesh &output) 00127 { 00128 // Copy the header 00129 output.header = input_->header; 00130 00131 if (!initCompute ()) 00132 { 00133 output.cloud.width = output.cloud.height = 1; 00134 output.cloud.data.clear (); 00135 output.polygons.clear (); 00136 return; 00137 } 00138 00139 // Check if a space search locator was given 00140 if (check_tree_) 00141 { 00142 if (!tree_) 00143 { 00144 if (input_->isOrganized ()) 00145 tree_.reset (new pcl::search::OrganizedNeighbor<PointInT> ()); 00146 else 00147 tree_.reset (new pcl::search::KdTree<PointInT> (false)); 00148 } 00149 00150 // Send the surface dataset to the spatial locator 00151 tree_->setInputCloud (input_, indices_); 00152 } 00153 00154 // Set up the output dataset 00155 pcl::toPCLPointCloud2 (*input_, output.cloud); 00156 // output.polygons.clear (); 00157 // output.polygons.reserve (2*indices_->size ()); /// NOTE: usually the number of triangles is around twice the number of vertices 00158 // Perform the actual surface reconstruction 00159 performReconstruction (output); 00160 00161 deinitCompute (); 00162 } 00163 00165 template <typename PointInT> void 00166 pcl::MeshConstruction<PointInT>::reconstruct (std::vector<pcl::Vertices> &polygons) 00167 { 00168 if (!initCompute ()) 00169 { 00170 polygons.clear (); 00171 return; 00172 } 00173 00174 // Check if a space search locator was given 00175 if (check_tree_) 00176 { 00177 if (!tree_) 00178 { 00179 if (input_->isOrganized ()) 00180 tree_.reset (new pcl::search::OrganizedNeighbor<PointInT> ()); 00181 else 00182 tree_.reset (new pcl::search::KdTree<PointInT> (false)); 00183 } 00184 00185 // Send the surface dataset to the spatial locator 00186 tree_->setInputCloud (input_, indices_); 00187 } 00188 00189 // Set up the output dataset 00190 //polygons.clear (); 00191 //polygons.reserve (2 * indices_->size ()); /// NOTE: usually the number of triangles is around twice the number of vertices 00192 // Perform the actual surface reconstruction 00193 performReconstruction (polygons); 00194 00195 deinitCompute (); 00196 } 00197 00198 00199 #endif // PCL_SURFACE_RECONSTRUCTION_IMPL_H_ 00200