Classes | Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
pcl::VoxelGridCovariance< PointT > Class Template Reference

A searchable voxel strucure containing the mean and covariance of the data. More...

#include <voxel_grid_covariance.h>

Inheritance diagram for pcl::VoxelGridCovariance< PointT >:
Inheritance graph
[legend]

List of all members.

Classes

struct  Leaf
 Simple structure to hold a centroid, covarince and the number of points in a leaf. Inverse covariance, eigen vectors and engen values are precomputed. More...

Public Types

typedef boost::shared_ptr
< const VoxelGrid< PointT > > 
ConstPtr
typedef const LeafLeafConstPtr
 Const pointer to VoxelGridCovariance leaf structure.
typedef LeafLeafPtr
 Pointer to VoxelGridCovariance leaf structure.
typedef boost::shared_ptr
< VoxelGrid< PointT > > 
Ptr

Public Member Functions

void filter (PointCloud &output, bool searchable=false)
 Filter cloud and initializes voxel structure.
void filter (bool searchable=false)
 Initializes voxel structure.
PointCloudPtr getCentroids ()
 Get a pointcloud containing the voxel centroids.
double getCovEigValueInflationRatio ()
 Get the minimum allowable ratio between eigenvalues to prevent singular covariance matrices.
void getDisplayCloud (pcl::PointCloud< PointXYZ > &cell_cloud)
 Get a cloud to visualize each voxels normal distribution.
LeafConstPtr getLeaf (int index)
 Get the voxel containing point p.
LeafConstPtr getLeaf (PointT &p)
 Get the voxel containing point p.
LeafConstPtr getLeaf (Eigen::Vector3f &p)
 Get the voxel containing point p.
const std::map< size_t, Leaf > & getLeaves ()
 Get the leaf structure map.
int getMinPointPerVoxel ()
 Get the minimum number of points required for a cell to be used.
int getNeighborhoodAtPoint (const PointT &reference_point, std::vector< LeafConstPtr > &neighbors)
 Get the voxels surrounding point p, not including the voxel contating point p.
int nearestKSearch (const PointT &point, int k, std::vector< LeafConstPtr > &k_leaves, std::vector< float > &k_sqr_distances)
 Search for the k-nearest occupied voxels for the given query point.
int nearestKSearch (const PointCloud &cloud, int index, int k, std::vector< LeafConstPtr > &k_leaves, std::vector< float > &k_sqr_distances)
 Search for the k-nearest occupied voxels for the given query point.
int radiusSearch (const PointT &point, double radius, std::vector< LeafConstPtr > &k_leaves, std::vector< float > &k_sqr_distances, unsigned int max_nn=0)
 Search for all the nearest occupied voxels of the query point in a given radius.
int radiusSearch (const PointCloud &cloud, int index, double radius, std::vector< LeafConstPtr > &k_leaves, std::vector< float > &k_sqr_distances, unsigned int max_nn=0)
 Search for all the nearest occupied voxels of the query point in a given radius.
void setCovEigValueInflationRatio (double min_covar_eigvalue_mult)
 Set the minimum allowable ratio between eigenvalues to prevent singular covariance matrices.
void setMinPointPerVoxel (int min_points_per_voxel)
 Set the minimum number of points required for a cell to be used (must be 3 or greater for covariance calculation).
 VoxelGridCovariance ()
 Constructor. Sets leaf_size_ to 0 and searchable_ to false.

Protected Types

typedef pcl::traits::fieldList
< PointT >::type 
FieldList
typedef Filter< PointT >
::PointCloud 
PointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr

Protected Member Functions

void applyFilter (PointCloud &output)
 Filter cloud and initializes voxel structure.

Protected Attributes

KdTreeFLANN< PointTkdtree_
 KdTree generated using voxel_centroids_ (used for searching).
std::map< size_t, Leafleaves_
 Voxel structure containing all leaf nodes (includes voxels with less than a sufficient number of points).
double min_covar_eigvalue_mult_
 Minimum allowable ratio between eigenvalues to prevent singular covariance matrices.
int min_points_per_voxel_
 Minimum points contained with in a voxel to allow it to be useable.
bool searchable_
 Flag to determine if voxel structure is searchable.
PointCloudPtr voxel_centroids_
 Point cloud containing centroids of voxels containing atleast minimum number of points.
std::vector< int > voxel_centroids_leaf_indices_
 Indices of leaf structurs associated with each point in voxel_centroids_ (used for searching).

Detailed Description

template<typename PointT>
class pcl::VoxelGridCovariance< PointT >

A searchable voxel strucure containing the mean and covariance of the data.

Note:
For more information please see Magnusson, M. (2009). The Three-Dimensional Normal-Distributions Transform — an Efficient Representation for Registration, Surface Analysis, and Loop Detection. PhD thesis, Orebro University. Orebro Studies in Technology 36
Author:
Brian Okorn (Space and Naval Warfare Systems Center Pacific)

Definition at line 57 of file voxel_grid_covariance.h.


Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr< const VoxelGrid<PointT> > pcl::VoxelGridCovariance< PointT >::ConstPtr

Reimplemented from pcl::VoxelGrid< PointT >.

Definition at line 88 of file voxel_grid_covariance.h.

template<typename PointT>
typedef pcl::traits::fieldList<PointT>::type pcl::VoxelGridCovariance< PointT >::FieldList [protected]

Reimplemented from pcl::VoxelGrid< PointT >.

Definition at line 80 of file voxel_grid_covariance.h.

template<typename PointT>
typedef const Leaf* pcl::VoxelGridCovariance< PointT >::LeafConstPtr

Const pointer to VoxelGridCovariance leaf structure.

Definition at line 194 of file voxel_grid_covariance.h.

template<typename PointT>
typedef Leaf* pcl::VoxelGridCovariance< PointT >::LeafPtr

Pointer to VoxelGridCovariance leaf structure.

Definition at line 191 of file voxel_grid_covariance.h.

template<typename PointT>
typedef Filter<PointT>::PointCloud pcl::VoxelGridCovariance< PointT >::PointCloud [protected]

Reimplemented from pcl::VoxelGrid< PointT >.

Definition at line 81 of file voxel_grid_covariance.h.

template<typename PointT>
typedef PointCloud::ConstPtr pcl::VoxelGridCovariance< PointT >::PointCloudConstPtr [protected]

Reimplemented from pcl::VoxelGrid< PointT >.

Definition at line 83 of file voxel_grid_covariance.h.

template<typename PointT>
typedef PointCloud::Ptr pcl::VoxelGridCovariance< PointT >::PointCloudPtr [protected]

Reimplemented from pcl::VoxelGrid< PointT >.

Definition at line 82 of file voxel_grid_covariance.h.

template<typename PointT>
typedef boost::shared_ptr< VoxelGrid<PointT> > pcl::VoxelGridCovariance< PointT >::Ptr

Reimplemented from pcl::VoxelGrid< PointT >.

Definition at line 87 of file voxel_grid_covariance.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::VoxelGridCovariance< PointT >::VoxelGridCovariance ( ) [inline]

Constructor. Sets leaf_size_ to 0 and searchable_ to false.

Definition at line 201 of file voxel_grid_covariance.h.


Member Function Documentation

template<typename PointT >
void pcl::VoxelGridCovariance< PointT >::applyFilter ( PointCloud output) [protected, virtual]

Filter cloud and initializes voxel structure.

Parameters:
[out]outputcloud containing centroids of voxels containing a sufficient number of points

Reimplemented from pcl::VoxelGrid< PointT >.

Definition at line 49 of file voxel_grid_covariance.hpp.

template<typename PointT>
void pcl::VoxelGridCovariance< PointT >::filter ( PointCloud output,
bool  searchable = false 
) [inline]

Filter cloud and initializes voxel structure.

Parameters:
[out]outputcloud containing centroids of voxels containing a sufficient number of points
[in]searchableflag if voxel structure is searchable, if true then kdtree is built

Definition at line 267 of file voxel_grid_covariance.h.

template<typename PointT>
void pcl::VoxelGridCovariance< PointT >::filter ( bool  searchable = false) [inline]

Initializes voxel structure.

Parameters:
[in]searchableflag if voxel structure is searchable, if true then kdtree is built

Definition at line 285 of file voxel_grid_covariance.h.

template<typename PointT>
PointCloudPtr pcl::VoxelGridCovariance< PointT >::getCentroids ( ) [inline]

Get a pointcloud containing the voxel centroids.

Note:
Only voxels containing a sufficient number of points are used.
Returns:
a map contataining all leaves

Definition at line 393 of file voxel_grid_covariance.h.

template<typename PointT>
double pcl::VoxelGridCovariance< PointT >::getCovEigValueInflationRatio ( ) [inline]

Get the minimum allowable ratio between eigenvalues to prevent singular covariance matrices.

Returns:
the minimum allowable ratio between eigenvalues

Definition at line 257 of file voxel_grid_covariance.h.

template<typename PointT >
void pcl::VoxelGridCovariance< PointT >::getDisplayCloud ( pcl::PointCloud< PointXYZ > &  cell_cloud)

Get a cloud to visualize each voxels normal distribution.

Parameters:
[out]acloud created by sampling the normal distributions of each voxel

Definition at line 408 of file voxel_grid_covariance.hpp.

template<typename PointT>
LeafConstPtr pcl::VoxelGridCovariance< PointT >::getLeaf ( int  index) [inline]

Get the voxel containing point p.

Parameters:
[in]indexthe index of the leaf structure node
Returns:
const pointer to leaf structure

Definition at line 303 of file voxel_grid_covariance.h.

template<typename PointT>
LeafConstPtr pcl::VoxelGridCovariance< PointT >::getLeaf ( PointT p) [inline]

Get the voxel containing point p.

Parameters:
[in]pthe point to get the leaf structure at
Returns:
const pointer to leaf structure

Definition at line 320 of file voxel_grid_covariance.h.

template<typename PointT>
LeafConstPtr pcl::VoxelGridCovariance< PointT >::getLeaf ( Eigen::Vector3f &  p) [inline]

Get the voxel containing point p.

Parameters:
[in]pthe point to get the leaf structure at
Returns:
const pointer to leaf structure

Definition at line 347 of file voxel_grid_covariance.h.

template<typename PointT>
const std::map<size_t, Leaf>& pcl::VoxelGridCovariance< PointT >::getLeaves ( ) [inline]

Get the leaf structure map.

Returns:
a map contataining all leaves

Definition at line 383 of file voxel_grid_covariance.h.

template<typename PointT>
int pcl::VoxelGridCovariance< PointT >::getMinPointPerVoxel ( ) [inline]

Get the minimum number of points required for a cell to be used.

Returns:
the minimum number of points for required for a voxel to be used

Definition at line 239 of file voxel_grid_covariance.h.

template<typename PointT>
int pcl::VoxelGridCovariance< PointT >::getNeighborhoodAtPoint ( const PointT reference_point,
std::vector< LeafConstPtr > &  neighbors 
)

Get the voxels surrounding point p, not including the voxel contating point p.

Note:
Only voxels containing a sufficient number of points are used (slower than radius search in practice).
Parameters:
[in]reference_pointthe point to get the leaf structure at
[out]neighbors
Returns:
number of neighbors found

Definition at line 373 of file voxel_grid_covariance.hpp.

template<typename PointT>
int pcl::VoxelGridCovariance< PointT >::nearestKSearch ( const PointT point,
int  k,
std::vector< LeafConstPtr > &  k_leaves,
std::vector< float > &  k_sqr_distances 
) [inline]

Search for the k-nearest occupied voxels for the given query point.

Note:
Only voxels containing a sufficient number of points are used.
Parameters:
[in]pointthe given query point
[in]kthe number of neighbors to search for
[out]k_leavesthe resultant leaves of the neighboring points
[out]k_sqr_distancesthe resultant squared distances to the neighboring points
Returns:
number of neighbors found

Definition at line 414 of file voxel_grid_covariance.h.

template<typename PointT>
int pcl::VoxelGridCovariance< PointT >::nearestKSearch ( const PointCloud cloud,
int  index,
int  k,
std::vector< LeafConstPtr > &  k_leaves,
std::vector< float > &  k_sqr_distances 
) [inline]

Search for the k-nearest occupied voxels for the given query point.

Note:
Only voxels containing a sufficient number of points are used.
Parameters:
[in]pointthe given query point
[in]kthe number of neighbors to search for
[out]k_leavesthe resultant leaves of the neighboring points
[out]k_sqr_distancesthe resultant squared distances to the neighboring points
Returns:
number of neighbors found

Definition at line 448 of file voxel_grid_covariance.h.

template<typename PointT>
int pcl::VoxelGridCovariance< PointT >::radiusSearch ( const PointT point,
double  radius,
std::vector< LeafConstPtr > &  k_leaves,
std::vector< float > &  k_sqr_distances,
unsigned int  max_nn = 0 
) [inline]

Search for all the nearest occupied voxels of the query point in a given radius.

Note:
Only voxels containing a sufficient number of points are used.
Parameters:
[in]pointthe given query point
[in]radiusthe radius of the sphere bounding all of p_q's neighbors
[out]k_leavesthe resultant leaves of the neighboring points
[out]k_sqr_distancesthe resultant squared distances to the neighboring points
Returns:
number of neighbors found

Definition at line 466 of file voxel_grid_covariance.h.

template<typename PointT>
int pcl::VoxelGridCovariance< PointT >::radiusSearch ( const PointCloud cloud,
int  index,
double  radius,
std::vector< LeafConstPtr > &  k_leaves,
std::vector< float > &  k_sqr_distances,
unsigned int  max_nn = 0 
) [inline]

Search for all the nearest occupied voxels of the query point in a given radius.

Note:
Only voxels containing a sufficient number of points are used.
Parameters:
[in]cloudthe given query point
[in]indexa valid index in cloud representing a valid (i.e., finite) query point
[in]radiusthe radius of the sphere bounding all of p_q's neighbors
[out]k_leavesthe resultant leaves of the neighboring points
[out]k_sqr_distancesthe resultant squared distances to the neighboring points
Returns:
number of neighbors found

Definition at line 501 of file voxel_grid_covariance.h.

template<typename PointT>
void pcl::VoxelGridCovariance< PointT >::setCovEigValueInflationRatio ( double  min_covar_eigvalue_mult) [inline]

Set the minimum allowable ratio between eigenvalues to prevent singular covariance matrices.

Parameters:
[in]min_points_per_voxelthe minimum allowable ratio between eigenvalues

Definition at line 248 of file voxel_grid_covariance.h.

template<typename PointT>
void pcl::VoxelGridCovariance< PointT >::setMinPointPerVoxel ( int  min_points_per_voxel) [inline]

Set the minimum number of points required for a cell to be used (must be 3 or greater for covariance calculation).

Parameters:
[in]min_points_per_voxelthe minimum number of points for required for a voxel to be used

Definition at line 222 of file voxel_grid_covariance.h.


Member Data Documentation

template<typename PointT>
KdTreeFLANN<PointT> pcl::VoxelGridCovariance< PointT >::kdtree_ [protected]

KdTree generated using voxel_centroids_ (used for searching).

Definition at line 536 of file voxel_grid_covariance.h.

template<typename PointT>
std::map<size_t, Leaf> pcl::VoxelGridCovariance< PointT >::leaves_ [protected]

Voxel structure containing all leaf nodes (includes voxels with less than a sufficient number of points).

Definition at line 527 of file voxel_grid_covariance.h.

template<typename PointT>
double pcl::VoxelGridCovariance< PointT >::min_covar_eigvalue_mult_ [protected]

Minimum allowable ratio between eigenvalues to prevent singular covariance matrices.

Definition at line 524 of file voxel_grid_covariance.h.

template<typename PointT>
int pcl::VoxelGridCovariance< PointT >::min_points_per_voxel_ [protected]

Minimum points contained with in a voxel to allow it to be useable.

Definition at line 521 of file voxel_grid_covariance.h.

template<typename PointT>
bool pcl::VoxelGridCovariance< PointT >::searchable_ [protected]

Flag to determine if voxel structure is searchable.

Definition at line 518 of file voxel_grid_covariance.h.

template<typename PointT>
PointCloudPtr pcl::VoxelGridCovariance< PointT >::voxel_centroids_ [protected]

Point cloud containing centroids of voxels containing atleast minimum number of points.

Definition at line 530 of file voxel_grid_covariance.h.

template<typename PointT>
std::vector<int> pcl::VoxelGridCovariance< PointT >::voxel_centroids_leaf_indices_ [protected]

Indices of leaf structurs associated with each point in voxel_centroids_ (used for searching).

Definition at line 533 of file voxel_grid_covariance.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:44