|
Point Cloud Library (PCL)
1.6.0
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Point Cloud Library (PCL) - www.pointclouds.org 00005 * Copyright (c) 2011, Dirk Holz, University of Bonn. 00006 * Copyright (c) 2010-2011, Willow Garage, Inc. 00007 * 00008 * All rights reserved. 00009 * 00010 * Redistribution and use in source and binary forms, with or without 00011 * modification, are permitted provided that the following conditions 00012 * are met: 00013 * 00014 * * Redistributions of source code must retain the above copyright 00015 * notice, this list of conditions and the following disclaimer. 00016 * * Redistributions in binary form must reproduce the above 00017 * copyright notice, this list of conditions and the following 00018 * disclaimer in the documentation and/or other materials provided 00019 * with the distribution. 00020 * * Neither the name of Willow Garage, Inc. nor the names of its 00021 * contributors may be used to endorse or promote products derived 00022 * from this software without specific prior written permission. 00023 * 00024 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00025 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00026 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00027 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00028 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00029 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00030 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00031 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00032 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00033 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00034 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00035 * POSSIBILITY OF SUCH DAMAGE. 00036 * 00037 * $Id: organized_fast_mesh.h 5036 2012-03-12 08:54:15Z rusu $ 00038 * 00039 */ 00040 00041 #ifndef PCL_SURFACE_ORGANIZED_FAST_MESH_H_ 00042 #define PCL_SURFACE_ORGANIZED_FAST_MESH_H_ 00043 00044 #include <pcl/common/angles.h> 00045 #include <pcl/surface/reconstruction.h> 00046 00047 namespace pcl 00048 { 00049 00057 template <typename PointInT> 00058 class OrganizedFastMesh : public MeshConstruction<PointInT> 00059 { 00060 public: 00061 using MeshConstruction<PointInT>::input_; 00062 using MeshConstruction<PointInT>::check_tree_; 00063 00064 typedef typename pcl::PointCloud<PointInT>::Ptr PointCloudPtr; 00065 00066 typedef std::vector<pcl::Vertices> Polygons; 00067 00068 enum TriangulationType 00069 { 00070 TRIANGLE_RIGHT_CUT, // _always_ "cuts" a quad from top left to bottom right 00071 TRIANGLE_LEFT_CUT, // _always_ "cuts" a quad from top right to bottom left 00072 TRIANGLE_ADAPTIVE_CUT, // "cuts" where possible and prefers larger differences in 'z' direction 00073 QUAD_MESH // create a simple quad mesh 00074 }; 00075 00077 OrganizedFastMesh () 00078 : max_edge_length_squared_ (0.025f) 00079 , triangle_pixel_size_ (1) 00080 , triangulation_type_ (QUAD_MESH) 00081 , store_shadowed_faces_ (false) 00082 , cos_angle_tolerance_ (fabsf (cosf (pcl::deg2rad (12.5f)))) 00083 { 00084 check_tree_ = false; 00085 }; 00086 00088 ~OrganizedFastMesh () {}; 00089 00093 inline void 00094 setMaxEdgeLength (float max_edge_length) 00095 { 00096 max_edge_length_squared_ = max_edge_length * max_edge_length; 00097 }; 00098 00103 inline void 00104 setTrianglePixelSize (int triangle_size) 00105 { 00106 triangle_pixel_size_ = std::max (1, (triangle_size - 1)); 00107 } 00108 00113 inline void 00114 setTriangulationType (TriangulationType type) 00115 { 00116 triangulation_type_ = type; 00117 } 00118 00122 inline void 00123 storeShadowedFaces (bool enable) 00124 { 00125 store_shadowed_faces_ = enable; 00126 } 00127 00128 protected: 00130 float max_edge_length_squared_; 00131 00133 int triangle_pixel_size_; 00134 00136 TriangulationType triangulation_type_; 00137 00139 bool store_shadowed_faces_; 00140 00141 float cos_angle_tolerance_; 00142 00146 void 00147 reconstructPolygons (std::vector<pcl::Vertices>& polygons); 00148 00152 virtual void 00153 performReconstruction (std::vector<pcl::Vertices> &polygons); 00154 00162 void 00163 performReconstruction (pcl::PolygonMesh &output); 00164 00172 inline void 00173 addTriangle (int a, int b, int c, int idx, std::vector<pcl::Vertices>& polygons) 00174 { 00175 assert (idx < static_cast<int> (polygons.size ())); 00176 polygons[idx].vertices.resize (3); 00177 polygons[idx].vertices[0] = a; 00178 polygons[idx].vertices[1] = b; 00179 polygons[idx].vertices[2] = c; 00180 } 00181 00190 inline void 00191 addQuad (int a, int b, int c, int d, int idx, std::vector<pcl::Vertices>& polygons) 00192 { 00193 assert (idx < static_cast<int> (polygons.size ())); 00194 polygons[idx].vertices.resize (4); 00195 polygons[idx].vertices[0] = a; 00196 polygons[idx].vertices[1] = b; 00197 polygons[idx].vertices[2] = c; 00198 polygons[idx].vertices[3] = d; 00199 } 00200 00209 inline void 00210 resetPointData (const int &point_index, pcl::PolygonMesh &mesh, const float &value = 0.0f, 00211 int field_x_idx = 0, int field_y_idx = 1, int field_z_idx = 2) 00212 { 00213 float new_value = value; 00214 memcpy (&mesh.cloud.data[point_index * mesh.cloud.point_step + mesh.cloud.fields[field_x_idx].offset], &new_value, sizeof (float)); 00215 memcpy (&mesh.cloud.data[point_index * mesh.cloud.point_step + mesh.cloud.fields[field_y_idx].offset], &new_value, sizeof (float)); 00216 memcpy (&mesh.cloud.data[point_index * mesh.cloud.point_step + mesh.cloud.fields[field_z_idx].offset], &new_value, sizeof (float)); 00217 } 00218 00223 inline bool 00224 isShadowed (const PointInT& point_a, const PointInT& point_b) 00225 { 00226 Eigen::Vector3f viewpoint = Eigen::Vector3f::Zero (); // TODO: allow for passing viewpoint information 00227 Eigen::Vector3f dir_a = viewpoint - point_a.getVector3fMap (); 00228 Eigen::Vector3f dir_b = point_b.getVector3fMap () - point_a.getVector3fMap (); 00229 float distance_to_points = dir_a.norm (); 00230 float distance_between_points = dir_b.norm (); 00231 float cos_angle = dir_a.dot (dir_b) / (distance_to_points*distance_between_points); 00232 if (cos_angle != cos_angle) 00233 cos_angle = 1.0f; 00234 return (fabs (cos_angle) >= cos_angle_tolerance_); 00235 // TODO: check for both: angle almost 0/180 _and_ distance between points larger than noise level 00236 } 00237 00243 inline bool 00244 isValidTriangle (const int& a, const int& b, const int& c) 00245 { 00246 if (!pcl::isFinite (input_->points[a])) return (false); 00247 if (!pcl::isFinite (input_->points[b])) return (false); 00248 if (!pcl::isFinite (input_->points[c])) return (false); 00249 return (true); 00250 } 00251 00257 inline bool 00258 isShadowedTriangle (const int& a, const int& b, const int& c) 00259 { 00260 if (isShadowed (input_->points[a], input_->points[b])) return (true); 00261 if (isShadowed (input_->points[b], input_->points[c])) return (true); 00262 if (isShadowed (input_->points[c], input_->points[a])) return (true); 00263 return (false); 00264 } 00265 00272 inline bool 00273 isValidQuad (const int& a, const int& b, const int& c, const int& d) 00274 { 00275 if (!pcl::isFinite (input_->points[a])) return (false); 00276 if (!pcl::isFinite (input_->points[b])) return (false); 00277 if (!pcl::isFinite (input_->points[c])) return (false); 00278 if (!pcl::isFinite (input_->points[d])) return (false); 00279 return (true); 00280 } 00281 00288 inline bool 00289 isShadowedQuad (const int& a, const int& b, const int& c, const int& d) 00290 { 00291 if (isShadowed (input_->points[a], input_->points[b])) return (true); 00292 if (isShadowed (input_->points[b], input_->points[c])) return (true); 00293 if (isShadowed (input_->points[c], input_->points[d])) return (true); 00294 if (isShadowed (input_->points[d], input_->points[a])) return (true); 00295 return (false); 00296 } 00297 00301 void 00302 makeQuadMesh (std::vector<pcl::Vertices>& polygons); 00303 00307 void 00308 makeRightCutMesh (std::vector<pcl::Vertices>& polygons); 00309 00313 void 00314 makeLeftCutMesh (std::vector<pcl::Vertices>& polygons); 00315 00319 void 00320 makeAdaptiveCutMesh (std::vector<pcl::Vertices>& polygons); 00321 }; 00322 } 00323 00324 #endif // PCL_SURFACE_ORGANIZED_FAST_MESH_H_
1.7.6.1