A searchable voxel strucure containing the mean and covariance of the data. More...
#include <voxel_grid_covariance.h>

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 Leaf * | LeafConstPtr |
| Const pointer to VoxelGridCovariance leaf structure. | |
| typedef Leaf * | LeafPtr |
| 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< PointT > | kdtree_ |
| KdTree generated using voxel_centroids_ (used for searching). | |
| std::map< size_t, Leaf > | leaves_ |
| 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). | |
A searchable voxel strucure containing the mean and covariance of the data.
Definition at line 57 of file voxel_grid_covariance.h.
| 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.
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.
| typedef const Leaf* pcl::VoxelGridCovariance< PointT >::LeafConstPtr |
Const pointer to VoxelGridCovariance leaf structure.
Definition at line 194 of file voxel_grid_covariance.h.
| typedef Leaf* pcl::VoxelGridCovariance< PointT >::LeafPtr |
Pointer to VoxelGridCovariance leaf structure.
Definition at line 191 of file voxel_grid_covariance.h.
typedef Filter<PointT>::PointCloud pcl::VoxelGridCovariance< PointT >::PointCloud [protected] |
Reimplemented from pcl::VoxelGrid< PointT >.
Definition at line 81 of file voxel_grid_covariance.h.
typedef PointCloud::ConstPtr pcl::VoxelGridCovariance< PointT >::PointCloudConstPtr [protected] |
Reimplemented from pcl::VoxelGrid< PointT >.
Definition at line 83 of file voxel_grid_covariance.h.
typedef PointCloud::Ptr pcl::VoxelGridCovariance< PointT >::PointCloudPtr [protected] |
Reimplemented from pcl::VoxelGrid< PointT >.
Definition at line 82 of file voxel_grid_covariance.h.
| 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.
| 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.
| void pcl::VoxelGridCovariance< PointT >::applyFilter | ( | PointCloud & | output | ) | [protected, virtual] |
Filter cloud and initializes voxel structure.
| [out] | output | cloud 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.
| void pcl::VoxelGridCovariance< PointT >::filter | ( | PointCloud & | output, |
| bool | searchable = false |
||
| ) | [inline] |
Filter cloud and initializes voxel structure.
| [out] | output | cloud containing centroids of voxels containing a sufficient number of points |
| [in] | searchable | flag if voxel structure is searchable, if true then kdtree is built |
Definition at line 267 of file voxel_grid_covariance.h.
| void pcl::VoxelGridCovariance< PointT >::filter | ( | bool | searchable = false | ) | [inline] |
Initializes voxel structure.
| [in] | searchable | flag if voxel structure is searchable, if true then kdtree is built |
Definition at line 285 of file voxel_grid_covariance.h.
| PointCloudPtr pcl::VoxelGridCovariance< PointT >::getCentroids | ( | ) | [inline] |
Get a pointcloud containing the voxel centroids.
Definition at line 393 of file voxel_grid_covariance.h.
| double pcl::VoxelGridCovariance< PointT >::getCovEigValueInflationRatio | ( | ) | [inline] |
Get the minimum allowable ratio between eigenvalues to prevent singular covariance matrices.
Definition at line 257 of file voxel_grid_covariance.h.
| void pcl::VoxelGridCovariance< PointT >::getDisplayCloud | ( | pcl::PointCloud< PointXYZ > & | cell_cloud | ) |
Get a cloud to visualize each voxels normal distribution.
| [out] | a | cloud created by sampling the normal distributions of each voxel |
Definition at line 408 of file voxel_grid_covariance.hpp.
| LeafConstPtr pcl::VoxelGridCovariance< PointT >::getLeaf | ( | int | index | ) | [inline] |
Get the voxel containing point p.
| [in] | index | the index of the leaf structure node |
Definition at line 303 of file voxel_grid_covariance.h.
| LeafConstPtr pcl::VoxelGridCovariance< PointT >::getLeaf | ( | PointT & | p | ) | [inline] |
Get the voxel containing point p.
| [in] | p | the point to get the leaf structure at |
Definition at line 320 of file voxel_grid_covariance.h.
| LeafConstPtr pcl::VoxelGridCovariance< PointT >::getLeaf | ( | Eigen::Vector3f & | p | ) | [inline] |
Get the voxel containing point p.
| [in] | p | the point to get the leaf structure at |
Definition at line 347 of file voxel_grid_covariance.h.
| const std::map<size_t, Leaf>& pcl::VoxelGridCovariance< PointT >::getLeaves | ( | ) | [inline] |
Get the leaf structure map.
Definition at line 383 of file voxel_grid_covariance.h.
| int pcl::VoxelGridCovariance< PointT >::getMinPointPerVoxel | ( | ) | [inline] |
Get the minimum number of points required for a cell to be used.
Definition at line 239 of file voxel_grid_covariance.h.
| 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.
| [in] | reference_point | the point to get the leaf structure at |
| [out] | neighbors |
Definition at line 373 of file voxel_grid_covariance.hpp.
| 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.
| [in] | point | the given query point |
| [in] | k | the number of neighbors to search for |
| [out] | k_leaves | the resultant leaves of the neighboring points |
| [out] | k_sqr_distances | the resultant squared distances to the neighboring points |
Definition at line 414 of file voxel_grid_covariance.h.
| 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.
| [in] | point | the given query point |
| [in] | k | the number of neighbors to search for |
| [out] | k_leaves | the resultant leaves of the neighboring points |
| [out] | k_sqr_distances | the resultant squared distances to the neighboring points |
Definition at line 448 of file voxel_grid_covariance.h.
| 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.
| [in] | point | the given query point |
| [in] | radius | the radius of the sphere bounding all of p_q's neighbors |
| [out] | k_leaves | the resultant leaves of the neighboring points |
| [out] | k_sqr_distances | the resultant squared distances to the neighboring points |
Definition at line 466 of file voxel_grid_covariance.h.
| 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.
| [in] | cloud | the given query point |
| [in] | index | a valid index in cloud representing a valid (i.e., finite) query point |
| [in] | radius | the radius of the sphere bounding all of p_q's neighbors |
| [out] | k_leaves | the resultant leaves of the neighboring points |
| [out] | k_sqr_distances | the resultant squared distances to the neighboring points |
Definition at line 501 of file voxel_grid_covariance.h.
| void pcl::VoxelGridCovariance< PointT >::setCovEigValueInflationRatio | ( | double | min_covar_eigvalue_mult | ) | [inline] |
Set the minimum allowable ratio between eigenvalues to prevent singular covariance matrices.
| [in] | min_points_per_voxel | the minimum allowable ratio between eigenvalues |
Definition at line 248 of file voxel_grid_covariance.h.
| 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).
| [in] | min_points_per_voxel | the minimum number of points for required for a voxel to be used |
Definition at line 222 of file voxel_grid_covariance.h.
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.
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.
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.
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.
bool pcl::VoxelGridCovariance< PointT >::searchable_ [protected] |
Flag to determine if voxel structure is searchable.
Definition at line 518 of file voxel_grid_covariance.h.
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.
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.