00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_SURFACE_GRID_PROJECTION_H_
00039 #define PCL_SURFACE_GRID_PROJECTION_H_
00040
00041 #include <pcl/surface/boost.h>
00042 #include <pcl/surface/reconstruction.h>
00043
00044 namespace pcl
00045 {
00047 const int I_SHIFT_EP[12][2] = {
00048 {0, 4}, {1, 5}, {2, 6}, {3, 7},
00049 {0, 1}, {1, 2}, {2, 3}, {3, 0},
00050 {4, 5}, {5, 6}, {6, 7}, {7, 4}
00051 };
00052
00053 const int I_SHIFT_PT[4] = {
00054 0, 4, 5, 7
00055 };
00056
00057 const int I_SHIFT_EDGE[3][2] = {
00058 {0,1}, {1,3}, {1,2}
00059 };
00060
00061
00071 template <typename PointNT>
00072 class GridProjection : public SurfaceReconstruction<PointNT>
00073 {
00074 public:
00075 typedef boost::shared_ptr<GridProjection<PointNT> > Ptr;
00076 typedef boost::shared_ptr<const GridProjection<PointNT> > ConstPtr;
00077
00078 using SurfaceReconstruction<PointNT>::input_;
00079 using SurfaceReconstruction<PointNT>::tree_;
00080
00081 typedef typename pcl::PointCloud<PointNT>::Ptr PointCloudPtr;
00082
00083 typedef typename pcl::KdTree<PointNT> KdTree;
00084 typedef typename pcl::KdTree<PointNT>::Ptr KdTreePtr;
00085
00087 struct Leaf
00088 {
00089 Leaf () : data_indices (), pt_on_surface (), vect_at_grid_pt () {}
00090
00091 std::vector<int> data_indices;
00092 Eigen::Vector4f pt_on_surface;
00093 Eigen::Vector3f vect_at_grid_pt;
00094 };
00095
00096 typedef boost::unordered_map<int, Leaf, boost::hash<int>, std::equal_to<int>, Eigen::aligned_allocator<int> > HashMap;
00097
00099 GridProjection ();
00100
00104 GridProjection (double in_resolution);
00105
00107 ~GridProjection ();
00108
00112 inline void
00113 setResolution (double resolution)
00114 {
00115 leaf_size_ = resolution;
00116 }
00117
00118 inline double
00119 getResolution () const
00120 {
00121 return (leaf_size_);
00122 }
00123
00133 inline void
00134 setPaddingSize (int padding_size)
00135 {
00136 padding_size_ = padding_size;
00137 }
00138 inline int
00139 getPaddingSize () const
00140 {
00141 return (padding_size_);
00142 }
00143
00148 inline void
00149 setNearestNeighborNum (int k)
00150 {
00151 k_ = k;
00152 }
00153 inline int
00154 getNearestNeighborNum () const
00155 {
00156 return (k_);
00157 }
00158
00163 inline void
00164 setMaxBinarySearchLevel (int max_binary_search_level)
00165 {
00166 max_binary_search_level_ = max_binary_search_level;
00167 }
00168 inline int
00169 getMaxBinarySearchLevel () const
00170 {
00171 return (max_binary_search_level_);
00172 }
00173
00175 inline const HashMap&
00176 getCellHashMap () const
00177 {
00178 return (cell_hash_map_);
00179 }
00180
00181 inline const std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> >&
00182 getVectorAtDataPoint () const
00183 {
00184 return (vector_at_data_point_);
00185 }
00186
00187 inline const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> >&
00188 getSurface () const
00189 {
00190 return (surface_);
00191 }
00192
00193 protected:
00197 void
00198 getBoundingBox ();
00199
00203 bool
00204 reconstructPolygons (std::vector<pcl::Vertices> &polygons);
00205
00215 void
00216 performReconstruction (pcl::PolygonMesh &output);
00217
00228 void
00229 performReconstruction (pcl::PointCloud<PointNT> &points,
00230 std::vector<pcl::Vertices> &polygons);
00231
00237 void
00238 scaleInputDataPoint (double scale_factor);
00239
00245 inline void
00246 getCellIndex (const Eigen::Vector4f &p, Eigen::Vector3i& index) const
00247 {
00248 for (int i = 0; i < 3; ++i)
00249 index[i] = static_cast<int> ((p[i] - min_p_(i)) / leaf_size_);
00250 }
00251
00257 inline void
00258 getCellCenterFromIndex (const Eigen::Vector3i &index, Eigen::Vector4f ¢er) const
00259 {
00260 for (int i = 0; i < 3; ++i)
00261 center[i] =
00262 min_p_[i] + static_cast<float> (index[i]) *
00263 static_cast<float> (leaf_size_) +
00264 static_cast<float> (leaf_size_) / 2.0f;
00265 }
00266
00271 void
00272 getVertexFromCellCenter (const Eigen::Vector4f &cell_center,
00273 std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > &pts) const;
00274
00279 inline int
00280 getIndexIn1D (const Eigen::Vector3i &index) const
00281 {
00282
00283 return (index[0] * data_size_ * data_size_ +
00284 index[1] * data_size_ + index[2]);
00285 }
00286
00292 inline void
00293 getIndexIn3D (int index_1d, Eigen::Vector3i& index_3d) const
00294 {
00295
00296 index_3d[0] = index_1d / (data_size_ * data_size_);
00297 index_1d -= index_3d[0] * data_size_ * data_size_;
00298 index_3d[1] = index_1d / data_size_;
00299 index_1d -= index_3d[1] * data_size_;
00300 index_3d[2] = index_1d;
00301 }
00302
00307 void
00308 fillPad (const Eigen::Vector3i &index);
00309
00314 void
00315 getDataPtsUnion (const Eigen::Vector3i &index, std::vector <int> &pt_union_indices);
00316
00323 void
00324 createSurfaceForCell (const Eigen::Vector3i &index, std::vector <int> &pt_union_indices);
00325
00326
00334 void
00335 getProjection (const Eigen::Vector4f &p, std::vector<int> &pt_union_indices, Eigen::Vector4f &projection);
00336
00344 void
00345 getProjectionWithPlaneFit (const Eigen::Vector4f &p,
00346 std::vector<int> &pt_union_indices,
00347 Eigen::Vector4f &projection);
00348
00349
00355 void
00356 getVectorAtPoint (const Eigen::Vector4f &p,
00357 std::vector <int> &pt_union_indices, Eigen::Vector3f &vo);
00358
00366 void
00367 getVectorAtPointKNN (const Eigen::Vector4f &p,
00368 std::vector<int> &k_indices,
00369 std::vector<float> &k_squared_distances,
00370 Eigen::Vector3f &vo);
00371
00376 double
00377 getMagAtPoint (const Eigen::Vector4f &p, const std::vector <int> &pt_union_indices);
00378
00384 double
00385 getD1AtPoint (const Eigen::Vector4f &p, const Eigen::Vector3f &vec,
00386 const std::vector <int> &pt_union_indices);
00387
00393 double
00394 getD2AtPoint (const Eigen::Vector4f &p, const Eigen::Vector3f &vec,
00395 const std::vector <int> &pt_union_indices);
00396
00405 bool
00406 isIntersected (const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > &end_pts,
00407 std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > &vect_at_end_pts,
00408 std::vector <int> &pt_union_indices);
00409
00418 void
00419 findIntersection (int level,
00420 const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > &end_pts,
00421 const std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > &vect_at_end_pts,
00422 const Eigen::Vector4f &start_pt,
00423 std::vector<int> &pt_union_indices,
00424 Eigen::Vector4f &intersection);
00425
00440 void
00441 storeVectAndSurfacePoint (int index_1d, const Eigen::Vector3i &index_3d,
00442 std::vector<int> &pt_union_indices, const Leaf &cell_data);
00443
00457 void
00458 storeVectAndSurfacePointKNN (int index_1d, const Eigen::Vector3i &index_3d, const Leaf &cell_data);
00459
00460 private:
00462 HashMap cell_hash_map_;
00463
00465 Eigen::Vector4f min_p_, max_p_;
00466
00468 double leaf_size_;
00469
00471 double gaussian_scale_;
00472
00474 int data_size_;
00475
00477 int max_binary_search_level_;
00478
00480 int k_;
00481
00483 int padding_size_;
00484
00486 PointCloudPtr data_;
00487
00489 std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > vector_at_data_point_;
00490
00492 std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > surface_;
00493
00495 boost::dynamic_bitset<> occupied_cell_list_;
00496
00498 std::string getClassName () const { return ("GridProjection"); }
00499
00500 public:
00501 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00502 };
00503 }
00504
00505 #endif // PCL_SURFACE_GRID_PROJECTION_H_
00506