|
Point Cloud Library (PCL)
1.4.0
|
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: gp3.h 3753 2011-12-31 23:30:57Z rusu $ 00037 * 00038 */ 00039 00040 #ifndef PCL_GP3_H_ 00041 #define PCL_GP3_H_ 00042 00043 // PCL includes 00044 #include "pcl/surface/reconstruction.h" 00045 00046 #include "pcl/ros/conversions.h" 00047 #include "pcl/kdtree/kdtree.h" 00048 #include <pcl/kdtree/kdtree_flann.h> 00049 #include <pcl/PolygonMesh.h> 00050 #include <pcl/TextureMesh.h> 00051 #include <boost/function.hpp> 00052 00053 #include <fstream> 00054 #include <iostream> 00055 00056 // add by ktran to export update function 00057 #include <pcl/pcl_macros.h> 00058 #include <pcl/point_types.h> 00059 00060 00061 namespace pcl 00062 { 00063 // add by ktran for Kdtree_flaan search 00064 struct SearchPoint : public PointXYZ 00065 { 00066 SearchPoint(float x, float y, float z) {this->x=x; this->y=y; this->z=z;} 00067 }; 00068 00077 inline bool 00078 isVisible (const Eigen::Vector2f &X, const Eigen::Vector2f &S1, const Eigen::Vector2f &S2, 00079 const Eigen::Vector2f &R = Eigen::Vector2f::Zero ()) 00080 { 00081 double a0 = S1[1] - S2[1]; 00082 double b0 = S2[0] - S1[0]; 00083 double c0 = S1[0]*S2[1] - S2[0]*S1[1]; 00084 double a1 = -X[1]; 00085 double b1 = X[0]; 00086 double c1 = 0; 00087 if (R != Eigen::Vector2f::Zero()) 00088 { 00089 a1 += R[1]; 00090 b1 -= R[0]; 00091 c1 = R[0]*X[1] - X[0]*R[1]; 00092 } 00093 double div = a0*b1 - b0*a1; 00094 double x = (b0*c1 - b1*c0) / div; 00095 double y = (a1*c0 - a0*c1) / div; 00096 00097 bool intersection_outside_XR; 00098 if (R == Eigen::Vector2f::Zero()) 00099 { 00100 if (X[0] > 0) 00101 intersection_outside_XR = (x <= 0) || (x >= X[0]); 00102 else if (X[0] < 0) 00103 intersection_outside_XR = (x >= 0) || (x <= X[0]); 00104 else if (X[1] > 0) 00105 intersection_outside_XR = (y <= 0) || (y >= X[1]); 00106 else if (X[1] < 0) 00107 intersection_outside_XR = (y >= 0) || (y <= X[1]); 00108 else 00109 intersection_outside_XR = true; 00110 } 00111 else 00112 { 00113 if (X[0] > R[0]) 00114 intersection_outside_XR = (x <= R[0]) || (x >= X[0]); 00115 else if (X[0] < R[0]) 00116 intersection_outside_XR = (x >= R[0]) || (x <= X[0]); 00117 else if (X[1] > R[1]) 00118 intersection_outside_XR = (y <= R[1]) || (y >= X[1]); 00119 else if (X[1] < R[1]) 00120 intersection_outside_XR = (y >= R[1]) || (y <= X[1]); 00121 else 00122 intersection_outside_XR = true; 00123 } 00124 if (intersection_outside_XR) 00125 return true; 00126 else 00127 { 00128 if (S1[0] > S2[0]) 00129 return (x <= S2[0]) || (x >= S1[0]); 00130 else if (S1[0] < S2[0]) 00131 return (x >= S2[0]) || (x <= S1[0]); 00132 else if (S1[1] > S2[1]) 00133 return (y <= S2[1]) || (y >= S1[1]); 00134 else if (S1[1] < S2[1]) 00135 return (y >= S2[1]) || (y <= S1[1]); 00136 else 00137 return false; 00138 } 00139 } 00140 00147 template <typename PointInT> 00148 class GreedyProjectionTriangulation : public MeshConstruction<PointInT> 00149 { 00150 public: 00151 using MeshConstruction<PointInT>::tree_; 00152 using MeshConstruction<PointInT>::input_; 00153 using MeshConstruction<PointInT>::indices_; 00154 00155 typedef typename pcl::KdTree<PointInT> KdTree; 00156 typedef typename pcl::KdTree<PointInT>::Ptr KdTreePtr; 00157 00158 typedef pcl::PointCloud<PointInT> PointCloudIn; 00159 typedef typename PointCloudIn::Ptr PointCloudInPtr; 00160 typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; 00161 00162 // FIXME this enum should have a type. Not be anonymous. 00163 // Otherplaces where consts are used probably should be fixed. 00164 enum 00165 { 00166 NONE = -1, // not-defined 00167 FREE = 0, 00168 FRINGE = 1, 00169 BOUNDARY = 2, 00170 COMPLETED = 3, 00171 }; 00172 00174 GreedyProjectionTriangulation () : nnn_ (0), mu_ (0), search_radius_ (0), 00175 minimum_angle_ (0), maximum_angle_ (0), 00176 eps_angle_(0), consistent_(false) 00177 {}; 00178 00183 inline void 00184 setMu (double mu) { mu_ = mu; } 00185 00187 inline double 00188 getMu () { return (mu_); } 00189 00193 inline void 00194 setMaximumNearestNeighbors (int nnn) { nnn_ = nnn; } 00195 00197 inline int 00198 getMaximumNearestNeighbors () { return (nnn_); } 00199 00204 inline void 00205 setSearchRadius (double radius) { search_radius_ = radius; } 00206 00208 inline double 00209 getSearchRadius () { return (search_radius_); } 00210 00215 inline void 00216 setMinimumAngle (double minimum_angle) { minimum_angle_ = minimum_angle; } 00217 00219 inline double 00220 getMinimumAngle () { return (minimum_angle_); } 00221 00226 inline void 00227 setMaximumAngle (double maximum_angle) { maximum_angle_ = maximum_angle; } 00228 00230 inline double 00231 getMaximumAngle () { return (maximum_angle_); } 00232 00238 inline void 00239 setMaximumSurfaceAngle (double eps_angle) { eps_angle_ = eps_angle; } 00240 00242 inline double 00243 getMaximumSurfaceAngle () { return (eps_angle_); } 00244 00248 inline void 00249 setNormalConsistency (bool consistent) { consistent_ = consistent; } 00250 00252 inline bool 00253 getNormalConsistency () { return (consistent_); } 00254 00258 inline std::vector<int> 00259 getPointStates () { return (state_); } 00260 00264 inline std::vector<int> 00265 getPartIDs () { return (part_); } 00266 00267 00269 inline std::vector<int> 00270 getSFN () { return (sfn_); } 00271 00273 inline std::vector<int> 00274 getFFN () { return (ffn_); } 00275 00280 void 00281 removeOverlapTriangles (pcl::PolygonMesh &mesh1, pcl::PolygonMesh &mesh2); 00282 00283 protected: 00285 int nnn_; 00286 00288 double mu_; 00289 00291 double search_radius_; 00292 00294 double minimum_angle_; 00295 00297 double maximum_angle_; 00298 00300 double eps_angle_; 00301 00303 bool consistent_; 00304 00305 private: 00307 struct nnAngle 00308 { 00309 double angle; 00310 int index; 00311 int nnIndex; 00312 bool visible; 00313 }; 00314 00316 struct doubleEdge 00317 { 00318 int index; 00319 Eigen::Vector2f first; 00320 Eigen::Vector2f second; 00321 }; 00322 00323 // Variables made global to decrease the number of parameters to helper functions 00324 00326 pcl::Vertices triangle_; 00328 std::vector<Eigen::Vector3f> coords_; 00329 00331 std::vector<nnAngle> angles_; 00333 int R_; 00335 std::vector<int> state_; 00337 std::vector<int> source_; 00339 std::vector<int> ffn_; 00341 std::vector<int> sfn_; 00343 std::vector<int> part_; 00345 std::vector<int> fringe_queue_; 00346 00348 bool is_current_free_; 00350 int current_index_; 00352 bool prev_is_ffn_; 00354 bool prev_is_sfn_; 00356 bool next_is_ffn_; 00358 bool next_is_sfn_; 00360 bool changed_1st_fn_; 00362 bool changed_2nd_fn_; 00364 int new2boundary_; 00365 00369 bool already_connected_; 00370 00372 Eigen::Vector3f proj_qp_; 00374 Eigen::Vector3f u_; 00376 Eigen::Vector3f v_; 00378 Eigen::Vector2f uvn_ffn_; 00380 Eigen::Vector2f uvn_sfn_; 00382 Eigen::Vector2f uvn_next_ffn_; 00384 Eigen::Vector2f uvn_next_sfn_; 00385 00387 Eigen::Vector3f tmp_; 00388 00392 void 00393 performReconstruction (pcl::PolygonMesh &output); 00394 00398 void 00399 performReconstruction (std::vector<pcl::Vertices> &polygons); 00400 00404 bool 00405 reconstructPolygons (std::vector<pcl::Vertices> &polygons); 00406 00408 std::string 00409 getClassName () const { return ("GreedyProjectionTriangulation"); } 00410 00421 void 00422 connectPoint (std::vector<pcl::Vertices> &polygons, 00423 const int prev_index, 00424 const int next_index, 00425 const int next_next_index, 00426 const Eigen::Vector2f &uvn_current, 00427 const Eigen::Vector2f &uvn_prev, 00428 const Eigen::Vector2f &uvn_next); 00429 00434 void 00435 closeTriangle (std::vector<pcl::Vertices> &polygons); 00436 00440 std::vector<std::vector<size_t> > 00441 getTriangleList (const pcl::PolygonMesh &input); 00442 00449 inline void 00450 addTriangle (int a, int b, int c, std::vector<pcl::Vertices> &polygons) 00451 { 00452 triangle_.vertices.resize (3); 00453 triangle_.vertices[0] = a; 00454 triangle_.vertices[1] = b; 00455 triangle_.vertices[2] = c; 00456 polygons.push_back (triangle_); 00457 } 00458 00463 inline void 00464 addFringePoint (int v, int s) 00465 { 00466 source_[v] = s; 00467 part_[v] = part_[s]; 00468 fringe_queue_.push_back(v); 00469 } 00470 00476 static inline bool 00477 nnAngleSortAsc (const nnAngle& a1, const nnAngle& a2) 00478 { 00479 if (a1.visible == a2.visible) 00480 return (a1.angle < a2.angle); 00481 else 00482 return a1.visible; 00483 } 00484 }; 00485 00486 } // namespace pcl 00487 00488 #endif //#ifndef PCL_GP3_H_ 00489
1.7.6.1