Classes | Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
pcl::GridProjection< PointNT > Class Template Reference

Grid projection surface reconstruction method. More...

#include <grid_projection.h>

Inheritance diagram for pcl::GridProjection< PointNT >:
Inheritance graph
[legend]

List of all members.

Classes

struct  Leaf
 Data leaf. More...

Public Types

typedef boost::unordered_map
< int, Leaf, boost::hash< int >
, std::equal_to< int >
, Eigen::aligned_allocator
< int > > 
HashMap
typedef pcl::KdTree< PointNT > KdTree
typedef pcl::KdTree< PointNT >::Ptr KdTreePtr
typedef pcl::PointCloud
< PointNT >::Ptr 
PointCloudPtr

Public Member Functions

const HashMapgetCellHashMap () const
int getMaxBinarySearchLevel () const
int getNearestNeighborNum () const
int getPaddingSize () const
double getResolution () const
const std::vector
< Eigen::Vector4f,
Eigen::aligned_allocator
< Eigen::Vector4f > > & 
getSurface () const
const std::vector
< Eigen::Vector3f,
Eigen::aligned_allocator
< Eigen::Vector3f > > & 
getVectorAtDataPoint () const
 GridProjection ()
 Constructor.
 GridProjection (double in_resolution)
 Constructor.
void setMaxBinarySearchLevel (int max_binary_search_level)
 Binary search is used in projection. given a point x, we find another point which is 3*cell_size_ far away from x. Then we do a binary search between these two points to find where the projected point should be.
void setNearestNeighborNum (int k)
 Set this only when using the k nearest neighbors search instead of finding the point union.
void setPaddingSize (int padding_size)
 When averaging the vectors, we find the union of all the input data points within the padding area,and do a weighted average. Say if the padding size is 1, when we process cell (x,y,z), we will find union of input data points from (x-1) to (x+1), (y-1) to (y+1), (z-1) to (z+1)(in total, 27 cells). In this way, even the cells itself doesnt contain any data points, we will stil process it because there are data points in the padding area. This can help us fix holes which is smaller than the padding size.
void setResolution (double resolution)
 Set the size of the grid cell.
 ~GridProjection ()
 Destructor.

Protected Member Functions

void createSurfaceForCell (const Eigen::Vector3i &index, std::vector< int > &pt_union_indices)
 Given the index of a cell, exam it's up, left, front edges, and add the vectices to m_surface list.the up, left, front edges only share 4 points, we first get the vectors at these 4 points and exam whether those three edges are intersected by the surface.
void fillPad (const Eigen::Vector3i &index)
 For a given 3d index of a cell, test whether the cells within its padding area exist in the hash table, if no, create an entry for that cell.
void findIntersection (int level, const std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &end_pts, const std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > &vect_at_end_pts, const Eigen::Vector4f &start_pt, std::vector< int > &pt_union_indices, Eigen::Vector4f &intersection)
 Find point where the edge intersects the surface.
void getBoundingBox ()
 Get the bounding box for the input data points, also calculating the cell size, and the gaussian scale factor.
void getCellCenterFromIndex (const Eigen::Vector3i &index, Eigen::Vector4f &center) const
 Given the 3d index (x, y, z) of the cell, get the coordinates of the cell center.
void getCellIndex (const Eigen::Vector4f &p, Eigen::Vector3i &index) const
 Get the 3d index (x,y,z) of the cell based on the location of the cell.
double getD1AtPoint (const Eigen::Vector4f &p, const Eigen::Vector3f &vec, const std::vector< int > &pt_union_indices)
 Get the 1st derivative.
double getD2AtPoint (const Eigen::Vector4f &p, const Eigen::Vector3f &vec, const std::vector< int > &pt_union_indices)
 Get the 2nd derivative.
void getDataPtsUnion (const Eigen::Vector3i &index, std::vector< int > &pt_union_indices)
 Obtain the index of a cell and the pad size.
int getIndexIn1D (const Eigen::Vector3i &index) const
 Given an index (x, y, z) in 3d, translate it into the index in 1d.
void getIndexIn3D (int index_1d, Eigen::Vector3i &index_3d) const
 Given an index in 1d, translate it into the index (x, y, z) in 3d.
double getMagAtPoint (const Eigen::Vector4f &p, const std::vector< int > &pt_union_indices)
 Get the magnitude of the vector by summing up the distance.
void getProjection (const Eigen::Vector4f &p, std::vector< int > &pt_union_indices, Eigen::Vector4f &projection)
 Given the coordinates of one point, project it onto the surface, return the projected point. Do a binary search between p and p+projection_distance to find the projected point.
void getProjectionWithPlaneFit (const Eigen::Vector4f &p, std::vector< int > &pt_union_indices, Eigen::Vector4f &projection)
 Given the coordinates of one point, project it onto the surface, return the projected point. Find the plane which fits all the points in pt_union_indices, projected p to the plane to get the projected point.
void getVectorAtPoint (const Eigen::Vector4f &p, std::vector< int > &pt_union_indices, Eigen::Vector3f &vo)
 Given the location of a point, get it's vector.
void getVectorAtPointKNN (const Eigen::Vector4f &p, std::vector< int > &k_indices, std::vector< float > &k_squared_distances, Eigen::Vector3f &vo)
 Given the location of a point, get it's vector.
void getVertexFromCellCenter (const Eigen::Vector4f &cell_center, std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &pts) const
 Given cell center, caluate the coordinates of the eight vertices of the cell.
bool isIntersected (const std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &end_pts, std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > &vect_at_end_pts, std::vector< int > &pt_union_indices)
 Test whether the edge is intersected by the surface by doing the dot product of the vector at two end points. Also test whether the edge is intersected by the maximum surface by examing the 2nd derivative of the intersection point.
void performReconstruction (pcl::PolygonMesh &output)
 Create the surface.
void performReconstruction (pcl::PointCloud< PointNT > &points, std::vector< pcl::Vertices > &polygons)
 Create the surface.
bool reconstructPolygons (std::vector< pcl::Vertices > &polygons)
 The actual surface reconstruction method.
void scaleInputDataPoint (double scale_factor)
 When the input data points don't fill into the 1*1*1 box, scale them so that they can be filled in the unit box. Otherwise, it will be some drawing problem when doing visulization.
void storeVectAndSurfacePoint (int index_1d, const Eigen::Vector3i &index_3d, std::vector< int > &pt_union_indices, const Leaf &cell_data)
 Go through all the entries in the hash table and update the cellData.
void storeVectAndSurfacePointKNN (int index_1d, const Eigen::Vector3i &index_3d, const Leaf &cell_data)
 Go through all the entries in the hash table and update the cellData. When creating the hash table, the pt_on_surface field store the center point of the cell.After calling this function, the projection operator will project the center point onto the surface, and the pt_on_surface field will be updated using the projected point.Also the vect_at_grid_pt field will be updated using the vector at the upper left front vertex of the cell. When projecting the point and calculating the vector, using K nearest neighbors instead of using the union of input data point within the cell and pads.

Private Member Functions

std::string getClassName () const
 Class get name method.

Private Attributes

HashMap cell_hash_map_
 Map containing the set of leaves.
PointCloudPtr data_
 The point cloud input (XYZ+Normals).
int data_size_
 Data size.
double gaussian_scale_
 Gaussian scale.
int k_
 Number of neighbors (k) to use.
double leaf_size_
 The size of a leaf.
int max_binary_search_level_
 Max binary search level.
Eigen::Vector4f max_p_
Eigen::Vector4f min_p_
 Min and max data points.
boost::dynamic_bitset occupied_cell_list_
 Bit map which tells if there is any input data point in the cell.
int padding_size_
 Padding size.
std::vector< Eigen::Vector4f,
Eigen::aligned_allocator
< Eigen::Vector4f > > 
surface_
 An array of points which lay on the output surface.
std::vector< Eigen::Vector3f,
Eigen::aligned_allocator
< Eigen::Vector3f > > 
vector_at_data_point_
 Store the surface normal(vector) at the each input data point.

Detailed Description

template<typename PointNT>
class pcl::GridProjection< PointNT >

Grid projection surface reconstruction method.

Author:
Rosie Li
Note:
If you use this code in any academic work, please cite:
  • Ruosi Li, Lu Liu, Ly Phan, Sasakthi Abeysinghe, Cindy Grimm, Tao Ju. Polygonizing extremal surfaces with manifold guarantees. In Proceedings of the 14th ACM Symposium on Solid and Physical Modeling, 2010.

Definition at line 73 of file grid_projection.h.


Member Typedef Documentation

template<typename PointNT>
typedef boost::unordered_map<int, Leaf, boost::hash<int>, std::equal_to<int>, Eigen::aligned_allocator<int> > pcl::GridProjection< PointNT >::HashMap

Definition at line 94 of file grid_projection.h.

template<typename PointNT>
typedef pcl::KdTree<PointNT> pcl::GridProjection< PointNT >::KdTree

Reimplemented from pcl::PCLSurfaceBase< PointNT >.

Definition at line 81 of file grid_projection.h.

template<typename PointNT>
typedef pcl::KdTree<PointNT>::Ptr pcl::GridProjection< PointNT >::KdTreePtr

Reimplemented from pcl::PCLSurfaceBase< PointNT >.

Definition at line 82 of file grid_projection.h.

template<typename PointNT>
typedef pcl::PointCloud<PointNT>::Ptr pcl::GridProjection< PointNT >::PointCloudPtr

Reimplemented from pcl::PCLBase< PointNT >.

Definition at line 79 of file grid_projection.h.


Constructor & Destructor Documentation

template<typename PointNT >
pcl::GridProjection< PointNT >::GridProjection ( )

Constructor.

Definition at line 49 of file grid_projection.hpp.

template<typename PointNT >
pcl::GridProjection< PointNT >::GridProjection ( double  in_resolution)

Constructor.

Parameters:
in_resolutionset the resolution of the grid

Definition at line 57 of file grid_projection.hpp.

template<typename PointNT >
pcl::GridProjection< PointNT >::~GridProjection ( )

Destructor.

Definition at line 65 of file grid_projection.hpp.


Member Function Documentation

template<typename PointNT >
void pcl::GridProjection< PointNT >::createSurfaceForCell ( const Eigen::Vector3i &  index,
std::vector< int > &  pt_union_indices 
) [protected]

Given the index of a cell, exam it's up, left, front edges, and add the vectices to m_surface list.the up, left, front edges only share 4 points, we first get the vectors at these 4 points and exam whether those three edges are intersected by the surface.

Parameters:
indexthe input index
pt_union_indicesthe union of input data points within the cell and padding cells

Definition at line 177 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::fillPad ( const Eigen::Vector3i &  index) [protected]

For a given 3d index of a cell, test whether the cells within its padding area exist in the hash table, if no, create an entry for that cell.

Parameters:
indexthe index of the cell in (x,y,z) format

Definition at line 561 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::findIntersection ( int  level,
const std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &  end_pts,
const std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > &  vect_at_end_pts,
const Eigen::Vector4f &  start_pt,
std::vector< int > &  pt_union_indices,
Eigen::Vector4f &  intersection 
) [protected]

Find point where the edge intersects the surface.

Parameters:
levelbinary search level
end_ptsthe two end points on the edge
vect_at_end_ptsthe vectors at the two end points
start_ptthe starting point we use for binary search
pt_union_indicesthe union of input data points within the cell and padding cells
intersectionthe resultant intersection point

Definition at line 510 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::getBoundingBox ( ) [protected]

Get the bounding box for the input data points, also calculating the cell size, and the gaussian scale factor.

Definition at line 90 of file grid_projection.hpp.

template<typename PointNT>
void pcl::GridProjection< PointNT >::getCellCenterFromIndex ( const Eigen::Vector3i &  index,
Eigen::Vector4f &  center 
) const [inline, protected]

Given the 3d index (x, y, z) of the cell, get the coordinates of the cell center.

Parameters:
indexthe output 3d index
centerthe resultant cell center

Definition at line 256 of file grid_projection.h.

template<typename PointNT>
const HashMap& pcl::GridProjection< PointNT >::getCellHashMap ( ) const [inline]

Definition at line 174 of file grid_projection.h.

template<typename PointNT>
void pcl::GridProjection< PointNT >::getCellIndex ( const Eigen::Vector4f &  p,
Eigen::Vector3i &  index 
) const [inline, protected]

Get the 3d index (x,y,z) of the cell based on the location of the cell.

Parameters:
pthe coordinate of the input point
indexthe output 3d index

Definition at line 244 of file grid_projection.h.

template<typename PointNT>
std::string pcl::GridProjection< PointNT >::getClassName ( ) const [inline, private, virtual]

Class get name method.

Reimplemented from pcl::PCLSurfaceBase< PointNT >.

Definition at line 496 of file grid_projection.h.

template<typename PointNT >
double pcl::GridProjection< PointNT >::getD1AtPoint ( const Eigen::Vector4f &  p,
const Eigen::Vector3f &  vec,
const std::vector< int > &  pt_union_indices 
) [protected]

Get the 1st derivative.

Parameters:
pthe coordinate of the input point
vecthe vector at point p
pt_union_indicesthe union of input data points within the cell and padding cells

Definition at line 449 of file grid_projection.hpp.

template<typename PointNT >
double pcl::GridProjection< PointNT >::getD2AtPoint ( const Eigen::Vector4f &  p,
const Eigen::Vector3f &  vec,
const std::vector< int > &  pt_union_indices 
) [protected]

Get the 2nd derivative.

Parameters:
pthe coordinate of the input point
vecthe vector at point p
pt_union_indicesthe union of input data points within the cell and padding cells

Definition at line 462 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::getDataPtsUnion ( const Eigen::Vector3i &  index,
std::vector< int > &  pt_union_indices 
) [protected]

Obtain the index of a cell and the pad size.

Parameters:
indexthe input index
pt_union_indicesthe union of input data points within the cell and padding cells

Definition at line 151 of file grid_projection.hpp.

template<typename PointNT>
int pcl::GridProjection< PointNT >::getIndexIn1D ( const Eigen::Vector3i &  index) const [inline, protected]

Given an index (x, y, z) in 3d, translate it into the index in 1d.

Parameters:
indexthe index of the cell in (x,y,z) 3d format

Definition at line 278 of file grid_projection.h.

template<typename PointNT>
void pcl::GridProjection< PointNT >::getIndexIn3D ( int  index_1d,
Eigen::Vector3i &  index_3d 
) const [inline, protected]

Given an index in 1d, translate it into the index (x, y, z) in 3d.

Parameters:
index_1dthe input 1d index
index_3dthe output 3d index

Definition at line 291 of file grid_projection.h.

template<typename PointNT >
double pcl::GridProjection< PointNT >::getMagAtPoint ( const Eigen::Vector4f &  p,
const std::vector< int > &  pt_union_indices 
) [protected]

Get the magnitude of the vector by summing up the distance.

Parameters:
pthe coordinate of the input point
pt_union_indicesthe union of input data points within the cell and padding cells

Definition at line 432 of file grid_projection.hpp.

template<typename PointNT>
int pcl::GridProjection< PointNT >::getMaxBinarySearchLevel ( ) const [inline]

Definition at line 167 of file grid_projection.h.

template<typename PointNT>
int pcl::GridProjection< PointNT >::getNearestNeighborNum ( ) const [inline]

Definition at line 152 of file grid_projection.h.

template<typename PointNT>
int pcl::GridProjection< PointNT >::getPaddingSize ( ) const [inline]

Definition at line 137 of file grid_projection.h.

template<typename PointNT >
void pcl::GridProjection< PointNT >::getProjection ( const Eigen::Vector4f &  p,
std::vector< int > &  pt_union_indices,
Eigen::Vector4f &  projection 
) [protected]

Given the coordinates of one point, project it onto the surface, return the projected point. Do a binary search between p and p+projection_distance to find the projected point.

Parameters:
pthe coordinates of the input point
pt_union_indicesthe union of input data points within the cell and padding cells
projectionthe resultant point projected

Definition at line 277 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::getProjectionWithPlaneFit ( const Eigen::Vector4f &  p,
std::vector< int > &  pt_union_indices,
Eigen::Vector4f &  projection 
) [protected]

Given the coordinates of one point, project it onto the surface, return the projected point. Find the plane which fits all the points in pt_union_indices, projected p to the plane to get the projected point.

Parameters:
pthe coordinates of the input point
pt_union_indicesthe union of input data points within the cell and padding cells
projectionthe resultant point projected
Remarks:
iterative weighted least squares or sac might give better results

Definition at line 316 of file grid_projection.hpp.

template<typename PointNT>
double pcl::GridProjection< PointNT >::getResolution ( ) const [inline]

Definition at line 117 of file grid_projection.h.

template<typename PointNT>
const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> >& pcl::GridProjection< PointNT >::getSurface ( ) const [inline]

Definition at line 186 of file grid_projection.h.

template<typename PointNT>
const std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> >& pcl::GridProjection< PointNT >::getVectorAtDataPoint ( ) const [inline]

Definition at line 180 of file grid_projection.h.

template<typename PointNT >
void pcl::GridProjection< PointNT >::getVectorAtPoint ( const Eigen::Vector4f &  p,
std::vector< int > &  pt_union_indices,
Eigen::Vector3f &  vo 
) [protected]

Given the location of a point, get it's vector.

Parameters:
pthe coordinates of the input point
pt_union_indicesthe union of input data points within the cell and padding cells
vothe resultant vector

Definition at line 351 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::getVectorAtPointKNN ( const Eigen::Vector4f &  p,
std::vector< int > &  k_indices,
std::vector< float > &  k_squared_distances,
Eigen::Vector3f &  vo 
) [protected]

Given the location of a point, get it's vector.

Parameters:
pthe coordinates of the input point
k_indicesthe k nearest neighbors of the query point
k_squared_distancesthe squared distances of the k nearest neighbors to the query point
vothe resultant vector

Definition at line 398 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::getVertexFromCellCenter ( const Eigen::Vector4f &  cell_center,
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &  pts 
) const [protected]

Given cell center, caluate the coordinates of the eight vertices of the cell.

Parameters:
cell_centerthe coordinates of the cell center
ptsthe coordinates of the 8 vertices

Definition at line 131 of file grid_projection.hpp.

template<typename PointNT >
bool pcl::GridProjection< PointNT >::isIntersected ( const std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &  end_pts,
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > &  vect_at_end_pts,
std::vector< int > &  pt_union_indices 
) [protected]

Test whether the edge is intersected by the surface by doing the dot product of the vector at two end points. Also test whether the edge is intersected by the maximum surface by examing the 2nd derivative of the intersection point.

Parameters:
end_ptsthe two points of the edge
vect_at_end_pts
pt_union_indicesthe union of input data points within the cell and padding cells

Definition at line 475 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::performReconstruction ( pcl::PolygonMesh &  output) [protected, virtual]

Create the surface.

The 1st step is filling the padding, so that all the cells in the padding area are in the hash map. The 2nd step is store the vector, and projected point. The 3rd step is finding all the edges intersects the surface, and creating surface.

Parameters:
[out]outputthe resultant polygonal mesh

Implements pcl::SurfaceReconstruction< PointNT >.

Definition at line 729 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::performReconstruction ( pcl::PointCloud< PointNT > &  points,
std::vector< pcl::Vertices > &  polygons 
) [protected, virtual]

Create the surface.

The 1st step is filling the padding, so that all the cells in the padding area are in the hash map. The 2nd step is store the vector, and projected point. The 3rd step is finding all the edges intersects the surface, and creating surface.

Parameters:
[out]pointsthe resultant points lying on the surface
[out]polygonsthe resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices.

Implements pcl::SurfaceReconstruction< PointNT >.

Definition at line 755 of file grid_projection.hpp.

template<typename PointNT >
bool pcl::GridProjection< PointNT >::reconstructPolygons ( std::vector< pcl::Vertices > &  polygons) [protected]

The actual surface reconstruction method.

Parameters:
[out]polygonsthe resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices.

Definition at line 625 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::scaleInputDataPoint ( double  scale_factor) [protected]

When the input data points don't fill into the 1*1*1 box, scale them so that they can be filled in the unit box. Otherwise, it will be some drawing problem when doing visulization.

Parameters:
scale_factorscale all the input data point by scale_factor

Definition at line 76 of file grid_projection.hpp.

template<typename PointNT>
void pcl::GridProjection< PointNT >::setMaxBinarySearchLevel ( int  max_binary_search_level) [inline]

Binary search is used in projection. given a point x, we find another point which is 3*cell_size_ far away from x. Then we do a binary search between these two points to find where the projected point should be.

Definition at line 162 of file grid_projection.h.

template<typename PointNT>
void pcl::GridProjection< PointNT >::setNearestNeighborNum ( int  k) [inline]

Set this only when using the k nearest neighbors search instead of finding the point union.

Parameters:
kThe number of nearest neighbors we are looking for

Definition at line 147 of file grid_projection.h.

template<typename PointNT>
void pcl::GridProjection< PointNT >::setPaddingSize ( int  padding_size) [inline]

When averaging the vectors, we find the union of all the input data points within the padding area,and do a weighted average. Say if the padding size is 1, when we process cell (x,y,z), we will find union of input data points from (x-1) to (x+1), (y-1) to (y+1), (z-1) to (z+1)(in total, 27 cells). In this way, even the cells itself doesnt contain any data points, we will stil process it because there are data points in the padding area. This can help us fix holes which is smaller than the padding size.

Parameters:
padding_sizeThe num of padding cells we want to create

Definition at line 132 of file grid_projection.h.

template<typename PointNT>
void pcl::GridProjection< PointNT >::setResolution ( double  resolution) [inline]

Set the size of the grid cell.

Parameters:
resolutionthe size of the grid cell

Definition at line 111 of file grid_projection.h.

template<typename PointNT >
void pcl::GridProjection< PointNT >::storeVectAndSurfacePoint ( int  index_1d,
const Eigen::Vector3i &  index_3d,
std::vector< int > &  pt_union_indices,
const Leaf cell_data 
) [protected]

Go through all the entries in the hash table and update the cellData.

When creating the hash table, the pt_on_surface field store the center point of the cell.After calling this function, the projection operator will project the center point onto the surface, and the pt_on_surface field will be updated using the projected point.Also the vect_at_grid_pt field will be updated using the vector at the upper left front vertex of the cell.

Parameters:
index_1dthe index of the cell after flatting it's 3d index into a 1d array
index_3dthe index of the cell in (x,y,z) 3d format
pt_union_indicesthe union of input data points within the cell and pads
cell_datainformation stored in the cell

Definition at line 584 of file grid_projection.hpp.

template<typename PointNT >
void pcl::GridProjection< PointNT >::storeVectAndSurfacePointKNN ( int  index_1d,
const Eigen::Vector3i &  index_3d,
const Leaf cell_data 
) [protected]

Go through all the entries in the hash table and update the cellData. When creating the hash table, the pt_on_surface field store the center point of the cell.After calling this function, the projection operator will project the center point onto the surface, and the pt_on_surface field will be updated using the projected point.Also the vect_at_grid_pt field will be updated using the vector at the upper left front vertex of the cell. When projecting the point and calculating the vector, using K nearest neighbors instead of using the union of input data point within the cell and pads.

Parameters:
index_1dthe index of the cell after flatting it's 3d index into a 1d array
index_3dthe index of the cell in (x,y,z) 3d format
cell_datainformation stored in the cell

Definition at line 602 of file grid_projection.hpp.


Member Data Documentation

template<typename PointNT>
HashMap pcl::GridProjection< PointNT >::cell_hash_map_ [private]

Map containing the set of leaves.

Definition at line 460 of file grid_projection.h.

template<typename PointNT>
PointCloudPtr pcl::GridProjection< PointNT >::data_ [private]

The point cloud input (XYZ+Normals).

Definition at line 484 of file grid_projection.h.

template<typename PointNT>
int pcl::GridProjection< PointNT >::data_size_ [private]

Data size.

Definition at line 472 of file grid_projection.h.

template<typename PointNT>
double pcl::GridProjection< PointNT >::gaussian_scale_ [private]

Gaussian scale.

Definition at line 469 of file grid_projection.h.

template<typename PointNT>
int pcl::GridProjection< PointNT >::k_ [private]

Number of neighbors (k) to use.

Definition at line 478 of file grid_projection.h.

template<typename PointNT>
double pcl::GridProjection< PointNT >::leaf_size_ [private]

The size of a leaf.

Definition at line 466 of file grid_projection.h.

template<typename PointNT>
int pcl::GridProjection< PointNT >::max_binary_search_level_ [private]

Max binary search level.

Definition at line 475 of file grid_projection.h.

template<typename PointNT>
Eigen::Vector4f pcl::GridProjection< PointNT >::max_p_ [private]

Definition at line 463 of file grid_projection.h.

template<typename PointNT>
Eigen::Vector4f pcl::GridProjection< PointNT >::min_p_ [private]

Min and max data points.

Definition at line 463 of file grid_projection.h.

template<typename PointNT>
boost::dynamic_bitset pcl::GridProjection< PointNT >::occupied_cell_list_ [private]

Bit map which tells if there is any input data point in the cell.

Definition at line 493 of file grid_projection.h.

template<typename PointNT>
int pcl::GridProjection< PointNT >::padding_size_ [private]

Padding size.

Definition at line 481 of file grid_projection.h.

template<typename PointNT>
std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > pcl::GridProjection< PointNT >::surface_ [private]

An array of points which lay on the output surface.

Definition at line 490 of file grid_projection.h.

template<typename PointNT>
std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > pcl::GridProjection< PointNT >::vector_at_data_point_ [private]

Store the surface normal(vector) at the each input data point.

Definition at line 487 of file grid_projection.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:30