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/reconstruction.h>
00042 #include <boost/dynamic_bitset/dynamic_bitset.hpp>
00043 #include <boost/unordered_map.hpp>
00044
00045 namespace pcl
00046 {
00048 const int I_SHIFT_EP[12][2] = {
00049 {0, 4}, {1, 5}, {2, 6}, {3, 7},
00050 {0, 1}, {1, 2}, {2, 3}, {3, 0},
00051 {4, 5}, {5, 6}, {6, 7}, {7, 4}
00052 };
00053
00054 const int I_SHIFT_PT[4] = {
00055 0, 4, 5, 7
00056 };
00057
00058 const int I_SHIFT_EDGE[3][2] = {
00059 {0,1}, {1,3}, {1,2}
00060 };
00061
00062
00066 template <typename PointNT>
00067 class GridProjection : public SurfaceReconstruction<PointNT>
00068 {
00069 public:
00070 using SurfaceReconstruction<PointNT>::input_;
00071 using SurfaceReconstruction<PointNT>::tree_;
00072
00073 typedef typename pcl::PointCloud<PointNT>::Ptr PointCloudPtr;
00074
00075 typedef typename pcl::KdTree<PointNT> KdTree;
00076 typedef typename pcl::KdTree<PointNT>::Ptr KdTreePtr;
00077
00078 typedef short int Index3D[3];
00079 typedef Eigen::Vector3f vector3d;
00080
00082 struct Leaf
00083 {
00084 std::vector<int> data_indices;
00085 Eigen::Vector4f pt_on_surface;
00086 vector3d vect_at_grid_pt;
00087 };
00088
00089 typedef boost::unordered_map<int, Leaf, boost::hash<int>, std::equal_to<int>, Eigen::aligned_allocator<int> > HashMap;
00090
00092 GridProjection ();
00093
00097 GridProjection (double in_resolution);
00098
00100 ~GridProjection ();
00101
00111 void
00112 performReconstruction (pcl::PolygonMesh &output);
00113
00117 inline void
00118 setResolution (double resolution)
00119 {
00120 leaf_size_ = resolution;
00121 }
00122
00123 inline double
00124 getResolution () const
00125 {
00126 return (leaf_size_);
00127 }
00128
00138 inline void
00139 setPaddingSize (int padding_size)
00140 {
00141 padding_size_ = padding_size;
00142 }
00143 inline int
00144 getPaddingSize () const
00145 {
00146 return (padding_size_);
00147 }
00148
00153 inline void
00154 setNearestNeighborNum (int k)
00155 {
00156 k_ = k;
00157 }
00158 inline int
00159 getNearestNeighborNum () const
00160 {
00161 return (k_);
00162 }
00163
00168 inline void
00169 setMaxBinarySearchLevel (int max_binary_search_level)
00170 {
00171 max_binary_search_level_ = max_binary_search_level;
00172 }
00173 inline int
00174 getMaxBinarySearchLevel () const
00175 {
00176 return (max_binary_search_level_);
00177 }
00178
00180 inline const HashMap&
00181 getCellHashMap () const
00182 {
00183 return (cell_hash_map_);
00184 }
00185
00186 inline const std::vector<vector3d>&
00187 getVectorAtDataPoint () const
00188 {
00189 return (vector_at_data_point_);
00190 }
00191
00192 inline const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> >&
00193 getSurface () const
00194 {
00195 return (surface_);
00196 }
00197
00201 void
00202 getBoundingBox ();
00203
00204 protected:
00210 void
00211 scaleInputDataPoint (double scale_factor);
00212
00218 inline void
00219 getCellIndex (const Eigen::Vector4f &p, Index3D& index) const
00220 {
00221 for (int i = 0; i < 3; ++i)
00222 index[i] = (p[i] - min_p_(i))/leaf_size_;
00223 }
00224
00230 inline void
00231 getCellCenterFromIndex (const Index3D &index, Eigen::Vector4f ¢er) const
00232 {
00233 for (int i = 0; i < 3; ++i)
00234 center[i] = min_p_[i] + index[i] * leaf_size_ + leaf_size_/2;
00235 }
00236
00241 void
00242 getVertexFromCellCenter (const Eigen::Vector4f &cell_center,
00243 Eigen::Vector4f (&pts)[8]) const;
00244
00249 void
00250 getVertexFromIndex (const Index3D &index, Eigen::Vector4f (&pts)[8]) const;
00251
00256 inline int
00257 getIndexIn1D (Index3D index) const
00258 {
00259
00260 return (index[0] * data_size_ * data_size_ +
00261 index[1] * data_size_ + index[2]);
00262 }
00263
00269 inline void
00270 getIndexIn3D (int index_1d, Index3D& index_3d) const
00271 {
00272
00273 index_3d[0] = index_1d / (data_size_ * data_size_);
00274 index_1d -= index_3d[0] * data_size_ * data_size_;
00275 index_3d[1] = index_1d / data_size_;
00276 index_1d -= index_3d[1] * data_size_;
00277 index_3d[2] = index_1d;
00278 }
00279
00284 void
00285 fillPad (const Index3D &index);
00286
00291 void
00292 getDataPtsUnion (const Index3D &index, std::vector <int> &pt_union_indices);
00293
00300 void
00301 createSurfaceForCell (const Index3D &index, std::vector <int> &pt_union_indices);
00302
00303
00310 Eigen::Vector4f
00311 getProjection (const Eigen::Vector4f &p, std::vector<int> &pt_union_indices);
00312
00319 Eigen::Vector4f
00320 getProjectionWithPlaneFit (const Eigen::Vector4f &p,
00321 std::vector<int> &pt_union_indices);
00322
00323
00328 Eigen::Vector3f
00329 getVectorAtPoint (const Eigen::Vector4f &p, std::vector <int> &pt_union_indices);
00334 Eigen::Vector3f
00335 getVectorAtPointKNN (const Eigen::Vector4f &p, std::vector<int> &k_indices,
00336 std::vector<float> &k_squared_distances);
00337
00342 double
00343 getMagAtPoint (const Eigen::Vector4f &p, const std::vector <int> &pt_union_indices);
00344
00350 double
00351 getD1AtPoint (const Eigen::Vector4f &p, const vector3d &vec,
00352 const std::vector <int> &pt_union_indices);
00353
00359 double
00360 getD2AtPoint (const Eigen::Vector4f &p, const vector3d &vec,
00361 const std::vector <int> &pt_union_indices);
00362
00369 bool
00370 isIntersected (const Eigen::Vector4f (&end_pts)[2], vector3d vect_at_end_pts[2],
00371 std::vector <int> &pt_union_indices);
00372
00380 Eigen::Vector4f
00381 findIntersection (int level, const Eigen::Vector4f (&end_pts)[2],
00382 vector3d vect_at_end_pts[2],
00383 const Eigen::Vector4f &start_pt,
00384 std::vector<int> &pt_union_indices);
00385
00400 void
00401 storeVectAndSurfacePoint (int index_1d, const Index3D &index_3d,
00402 std::vector<int> &pt_union_indices, const Leaf &cell_data);
00403
00417 void
00418 storeVectAndSurfacePointKNN (int index_1d, Index3D index_3d, Leaf cell_data);
00419
00420 private:
00422 HashMap cell_hash_map_;
00423
00425 Eigen::Vector4f min_p_, max_p_;
00426
00428 double leaf_size_;
00429
00431 double gaussian_scale_;
00432
00434 int data_size_;
00435
00437 int max_binary_search_level_;
00438
00440 int k_;
00441
00443 int padding_size_;
00444
00446 PointCloudPtr data_;
00447
00449 std::vector<vector3d> vector_at_data_point_;
00450
00452 std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > surface_;
00453
00455 boost::dynamic_bitset<> occupied_cell_list_;
00456
00458 std::string getClassName () const { return ("GridProjection"); }
00459
00460 public:
00461 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00462 };
00463 }
00464
00465 #endif // PCL_SURFACE_GRID_PROJECTION_H_
00466