|
Point Cloud Library (PCL)
1.7.2
|
A searchable voxel strucure containing the mean and covariance of the data. More...
#include <pcl/filters/voxel_grid_covariance.h>
Inheritance diagram for pcl::VoxelGridCovariance< PointT >:Classes | |
| struct | Leaf |
| Simple structure to hold a centroid, covarince and the number of points in a leaf. More... | |
Public Types | |
| typedef boost::shared_ptr< VoxelGrid< PointT > > | Ptr |
| typedef boost::shared_ptr< const VoxelGrid< PointT > > | ConstPtr |
| typedef Leaf * | LeafPtr |
| Pointer to VoxelGridCovariance leaf structure. More... | |
| typedef const Leaf * | LeafConstPtr |
| Const pointer to VoxelGridCovariance leaf structure. More... | |
Public Types inherited from pcl::Filter< PointT > | |
| typedef boost::shared_ptr< Filter< PointT > > | Ptr |
| typedef boost::shared_ptr< const Filter< PointT > > | ConstPtr |
| typedef pcl::PointCloud< PointT > | PointCloud |
| typedef PointCloud::Ptr | PointCloudPtr |
| typedef PointCloud::ConstPtr | PointCloudConstPtr |
Public Types inherited from pcl::PCLBase< PointT > | |
| typedef pcl::PointCloud< PointT > | PointCloud |
| typedef PointCloud::Ptr | PointCloudPtr |
| typedef PointCloud::ConstPtr | PointCloudConstPtr |
| typedef boost::shared_ptr< PointIndices > | PointIndicesPtr |
| typedef boost::shared_ptr< PointIndices const > | PointIndicesConstPtr |
Public Member Functions | |
| VoxelGridCovariance () | |
| Constructor. More... | |
| 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). More... | |
| int | getMinPointPerVoxel () |
| Get the minimum number of points required for a cell to be used. More... | |
| void | setCovEigValueInflationRatio (double min_covar_eigvalue_mult) |
| Set the minimum allowable ratio between eigenvalues to prevent singular covariance matrices. More... | |
| double | getCovEigValueInflationRatio () |
| Get the minimum allowable ratio between eigenvalues to prevent singular covariance matrices. More... | |
| void | filter (PointCloud &output, bool searchable=false) |
| Filter cloud and initializes voxel structure. More... | |
| void | filter (bool searchable=false) |
| Initializes voxel structure. More... | |
| LeafConstPtr | getLeaf (int index) |
| Get the voxel containing point p. More... | |
| LeafConstPtr | getLeaf (PointT &p) |
| Get the voxel containing point p. More... | |
| LeafConstPtr | getLeaf (Eigen::Vector3f &p) |
| Get the voxel containing point p. More... | |
| int | getNeighborhoodAtPoint (const PointT &reference_point, std::vector< LeafConstPtr > &neighbors) |
| Get the voxels surrounding point p, not including the voxel contating point p. More... | |
| const std::map< size_t, Leaf > & | getLeaves () |
| Get the leaf structure map. More... | |
| PointCloudPtr | getCentroids () |
| Get a pointcloud containing the voxel centroids. More... | |
| void | getDisplayCloud (pcl::PointCloud< PointXYZ > &cell_cloud) |
| Get a cloud to visualize each voxels normal distribution. More... | |
| 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. More... | |
| 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. More... | |
| 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. More... | |
| 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. More... | |
Public Member Functions inherited from pcl::VoxelGrid< PointT > | |
| VoxelGrid () | |
| Empty constructor. More... | |
| virtual | ~VoxelGrid () |
| Destructor. More... | |
| void | setLeafSize (const Eigen::Vector4f &leaf_size) |
| Set the voxel grid leaf size. More... | |
| void | setLeafSize (float lx, float ly, float lz) |
| Set the voxel grid leaf size. More... | |
| Eigen::Vector3f | getLeafSize () |
| Get the voxel grid leaf size. More... | |
| void | setDownsampleAllData (bool downsample) |
| Set to true if all fields need to be downsampled, or false if just XYZ. More... | |
| bool | getDownsampleAllData () |
| Get the state of the internal downsampling parameter (true if all fields need to be downsampled, false if just XYZ). More... | |
| void | setMinimumPointsNumberPerVoxel (unsigned int min_points_per_voxel) |
| Set the minimum number of points required for a voxel to be used. More... | |
| unsigned int | getMinimumPointsNumberPerVoxel () |
| Return the minimum number of points required for a voxel to be used. More... | |
| void | setSaveLeafLayout (bool save_leaf_layout) |
| Set to true if leaf layout information needs to be saved for later access. More... | |
| bool | getSaveLeafLayout () |
| Returns true if leaf layout information will to be saved for later access. More... | |
| Eigen::Vector3i | getMinBoxCoordinates () |
| Get the minimum coordinates of the bounding box (after filtering is performed). More... | |
| Eigen::Vector3i | getMaxBoxCoordinates () |
| Get the minimum coordinates of the bounding box (after filtering is performed). More... | |
| Eigen::Vector3i | getNrDivisions () |
| Get the number of divisions along all 3 axes (after filtering is performed). More... | |
| Eigen::Vector3i | getDivisionMultiplier () |
| Get the multipliers to be applied to the grid coordinates in order to find the centroid index (after filtering is performed). More... | |
| int | getCentroidIndex (const PointT &p) |
| Returns the index in the resulting downsampled cloud of the specified point. More... | |
| std::vector< int > | getNeighborCentroidIndices (const PointT &reference_point, const Eigen::MatrixXi &relative_coordinates) |
| Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinates, relative to the grid coordinates of the specified point (or -1 if the cell was empty/out of bounds). More... | |
| std::vector< int > | getLeafLayout () |
| Returns the layout of the leafs for fast access to cells relative to current position. More... | |
| Eigen::Vector3i | getGridCoordinates (float x, float y, float z) |
| Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). More... | |
| int | getCentroidIndexAt (const Eigen::Vector3i &ijk) |
| Returns the index in the downsampled cloud corresponding to a given set of coordinates. More... | |
| void | setFilterFieldName (const std::string &field_name) |
| Provide the name of the field to be used for filtering data. More... | |
| std::string const | getFilterFieldName () |
| Get the name of the field used for filtering. More... | |
| void | setFilterLimits (const double &limit_min, const double &limit_max) |
| Set the field filter limits. More... | |
| void | getFilterLimits (double &limit_min, double &limit_max) |
| Get the field filter limits (min/max) set by the user. More... | |
| void | setFilterLimitsNegative (const bool limit_negative) |
| Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). More... | |
| void | getFilterLimitsNegative (bool &limit_negative) |
| Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More... | |
| bool | getFilterLimitsNegative () |
| Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More... | |
Public Member Functions inherited from pcl::Filter< PointT > | |
| Filter (bool extract_removed_indices=false) | |
| Empty constructor. More... | |
| virtual | ~Filter () |
| Empty destructor. More... | |
| IndicesConstPtr const | getRemovedIndices () |
| Get the point indices being removed. More... | |
| void | getRemovedIndices (PointIndices &pi) |
| Get the point indices being removed. More... | |
| void | filter (PointCloud &output) |
| Calls the filtering method and returns the filtered dataset in output. More... | |
Public Member Functions inherited from pcl::PCLBase< PointT > | |
| PCLBase () | |
| Empty constructor. More... | |
| PCLBase (const PCLBase &base) | |
| Copy constructor. More... | |
| virtual | ~PCLBase () |
| Destructor. More... | |
| virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
| Provide a pointer to the input dataset. More... | |
| PointCloudConstPtr const | getInputCloud () const |
| Get a pointer to the input point cloud dataset. More... | |
| virtual void | setIndices (const IndicesPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. More... | |
| virtual void | setIndices (const IndicesConstPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. More... | |
| virtual void | setIndices (const PointIndicesConstPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. More... | |
| virtual void | setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols) |
| Set the indices for the points laying within an interest region of the point cloud. More... | |
| IndicesPtr const | getIndices () |
| Get a pointer to the vector of indices used. More... | |
| IndicesConstPtr const | getIndices () const |
| Get a pointer to the vector of indices used. More... | |
| const PointT & | operator[] (size_t pos) const |
| Override PointCloud operator[] to shorten code. More... | |
Protected Types | |
| typedef pcl::traits::fieldList< PointT >::type | FieldList |
| typedef Filter< PointT >::PointCloud | PointCloud |
| typedef PointCloud::Ptr | PointCloudPtr |
| typedef PointCloud::ConstPtr | PointCloudConstPtr |
Protected Types inherited from pcl::VoxelGrid< PointT > | |
| typedef Filter< PointT >::PointCloud | PointCloud |
| typedef PointCloud::Ptr | PointCloudPtr |
| typedef PointCloud::ConstPtr | PointCloudConstPtr |
| typedef boost::shared_ptr< VoxelGrid< PointT > > | Ptr |
| typedef boost::shared_ptr< const VoxelGrid< PointT > > | ConstPtr |
| typedef pcl::traits::fieldList< PointT >::type | FieldList |
Protected Member Functions | |
| void | applyFilter (PointCloud &output) |
| Filter cloud and initializes voxel structure. More... | |
Protected Member Functions inherited from pcl::Filter< PointT > | |
| const std::string & | getClassName () const |
| Get a string representation of the name of this class. More... | |
Protected Member Functions inherited from pcl::PCLBase< PointT > | |
| bool | initCompute () |
| This method should get called before starting the actual computation. More... | |
| bool | deinitCompute () |
| This method should get called after finishing the actual computation. More... | |
Protected Attributes | |
| bool | searchable_ |
| Flag to determine if voxel structure is searchable. More... | |
| int | min_points_per_voxel_ |
| Minimum points contained with in a voxel to allow it to be useable. More... | |
| double | min_covar_eigvalue_mult_ |
| Minimum allowable ratio between eigenvalues to prevent singular covariance matrices. More... | |
| std::map< size_t, Leaf > | leaves_ |
| Voxel structure containing all leaf nodes (includes voxels with less than a sufficient number of points). More... | |
| PointCloudPtr | voxel_centroids_ |
| Point cloud containing centroids of voxels containing atleast minimum number of points. More... | |
| std::vector< int > | voxel_centroids_leaf_indices_ |
| Indices of leaf structurs associated with each point in voxel_centroids_ (used for searching). More... | |
| KdTreeFLANN< PointT > | kdtree_ |
| KdTree generated using voxel_centroids_ (used for searching). More... | |
Protected Attributes inherited from pcl::VoxelGrid< PointT > | |
| Eigen::Vector4f | leaf_size_ |
| The size of a leaf. More... | |
| Eigen::Array4f | inverse_leaf_size_ |
| Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons. More... | |
| bool | downsample_all_data_ |
| Set to true if all fields need to be downsampled, or false if just XYZ. More... | |
| bool | save_leaf_layout_ |
| Set to true if leaf layout information needs to be saved in leaf_layout_. More... | |
| std::vector< int > | leaf_layout_ |
| The leaf layout information for fast access to cells relative to current position. More... | |
| Eigen::Vector4i | min_b_ |
| The minimum and maximum bin coordinates, the number of divisions, and the division multiplier. More... | |
| Eigen::Vector4i | max_b_ |
| Eigen::Vector4i | div_b_ |
| Eigen::Vector4i | divb_mul_ |
| std::string | filter_field_name_ |
| The desired user filter field name. More... | |
| double | filter_limit_min_ |
| The minimum allowed filter value a point will be considered from. More... | |
| double | filter_limit_max_ |
| The maximum allowed filter value a point will be considered from. More... | |
| bool | filter_limit_negative_ |
| Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). More... | |
| unsigned int | min_points_per_voxel_ |
| Minimum number of points per voxel for the centroid to be computed. More... | |
Protected Attributes inherited from pcl::Filter< PointT > | |
| IndicesPtr | removed_indices_ |
| Indices of the points that are removed. More... | |
| std::string | filter_name_ |
| The filter name. More... | |
| bool | extract_removed_indices_ |
| Set to true if we want to return the indices of the removed points. More... | |
Protected Attributes inherited from pcl::PCLBase< PointT > | |
| PointCloudConstPtr | input_ |
| The input point cloud dataset. More... | |
| IndicesPtr | indices_ |
| A pointer to the vector of point indices to use. More... | |
| bool | use_indices_ |
| Set to true if point indices are used. More... | |
| bool | fake_indices_ |
| If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More... | |
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 |
Definition at line 88 of file voxel_grid_covariance.h.
|
protected |
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.
|
protected |
Definition at line 81 of file voxel_grid_covariance.h.
|
protected |
Definition at line 83 of file voxel_grid_covariance.h.
|
protected |
Definition at line 82 of file voxel_grid_covariance.h.
| typedef boost::shared_ptr< VoxelGrid<PointT> > pcl::VoxelGridCovariance< PointT >::Ptr |
Definition at line 87 of file voxel_grid_covariance.h.
|
inline |
Constructor.
Sets leaf_size_ to 0 and searchable_ to false.
Definition at line 201 of file voxel_grid_covariance.h.
|
protectedvirtual |
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.
References pcl::PointCloud< PointT >::back(), pcl::VoxelGridCovariance< PointT >::Leaf::centroid, pcl::PointCloud< PointT >::clear(), pcl::VoxelGridCovariance< PointT >::Leaf::cov_, pcl::VoxelGridCovariance< PointT >::Leaf::evals_, pcl::VoxelGridCovariance< PointT >::Leaf::evecs_, pcl::getFieldIndex(), pcl::PointCloud< PointT >::height, pcl::VoxelGridCovariance< PointT >::Leaf::icov_, pcl::PointCloud< PointT >::is_dense, pcl::VoxelGridCovariance< PointT >::Leaf::mean_, pcl::VoxelGridCovariance< PointT >::Leaf::nr_points, pcl::PointCloud< PointT >::points, pcl::PointCloud< PointT >::push_back(), and pcl::PointCloud< PointT >::width.
Referenced by pcl::VoxelGridCovariance< PointTarget >::filter(), and pcl::VoxelGridCovariance< PointTarget >::radiusSearch().
|
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.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::init().
|
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.
|
inline |
Get a pointcloud containing the voxel centroids.
Definition at line 393 of file voxel_grid_covariance.h.
|
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] | cell_cloud | a cloud created by sampling the normal distributions of each voxel |
Definition at line 408 of file voxel_grid_covariance.hpp.
References pcl::PointCloud< PointT >::clear(), pcl::VoxelGridCovariance< PointT >::Leaf::cov_, pcl::VoxelGridCovariance< PointT >::Leaf::mean_, pcl::VoxelGridCovariance< PointT >::Leaf::nr_points, and pcl::PointCloud< PointT >::push_back().
Referenced by pcl::VoxelGridCovariance< PointTarget >::getCentroids().
|
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.
|
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.
|
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.
|
inline |
Get the leaf structure map.
Definition at line 383 of file voxel_grid_covariance.h.
|
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.
References pcl::getAllNeighborCellIndices().
Referenced by pcl::VoxelGridCovariance< PointTarget >::getLeaf().
|
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.
Referenced by pcl::VoxelGridCovariance< PointTarget >::nearestKSearch().
|
inline |
Search for the k-nearest occupied voxels for the given query point.
| [in] | cloud | the given query point |
| [in] | index | the index |
| [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 449 of file voxel_grid_covariance.h.
|
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 |
| [in] | max_nn |
Definition at line 468 of file voxel_grid_covariance.h.
Referenced by pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeDerivatives(), pcl::NormalDistributionsTransform< PointSource, PointTarget >::computeHessian(), and pcl::VoxelGridCovariance< PointTarget >::radiusSearch().
|
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 |
| [in] | max_nn |
Definition at line 504 of file voxel_grid_covariance.h.
|
inline |
Set the minimum allowable ratio between eigenvalues to prevent singular covariance matrices.
| [in] | min_covar_eigvalue_mult | the minimum allowable ratio between eigenvalues |
Definition at line 248 of file voxel_grid_covariance.h.
|
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.
|
protected |
KdTree generated using voxel_centroids_ (used for searching).
Definition at line 539 of file voxel_grid_covariance.h.
Referenced by pcl::VoxelGridCovariance< PointTarget >::filter(), pcl::VoxelGridCovariance< PointTarget >::nearestKSearch(), and pcl::VoxelGridCovariance< PointTarget >::radiusSearch().
|
protected |
Voxel structure containing all leaf nodes (includes voxels with less than a sufficient number of points).
Definition at line 530 of file voxel_grid_covariance.h.
Referenced by pcl::VoxelGridCovariance< PointTarget >::getLeaf(), pcl::VoxelGridCovariance< PointTarget >::getLeaves(), pcl::VoxelGridCovariance< PointTarget >::nearestKSearch(), and pcl::VoxelGridCovariance< PointTarget >::radiusSearch().
|
protected |
Minimum allowable ratio between eigenvalues to prevent singular covariance matrices.
Definition at line 527 of file voxel_grid_covariance.h.
Referenced by pcl::VoxelGridCovariance< PointTarget >::getCovEigValueInflationRatio(), and pcl::VoxelGridCovariance< PointTarget >::setCovEigValueInflationRatio().
|
protected |
Minimum points contained with in a voxel to allow it to be useable.
Definition at line 524 of file voxel_grid_covariance.h.
Referenced by pcl::VoxelGridCovariance< PointTarget >::getMinPointPerVoxel(), and pcl::VoxelGridCovariance< PointTarget >::setMinPointPerVoxel().
|
protected |
Flag to determine if voxel structure is searchable.
Definition at line 521 of file voxel_grid_covariance.h.
Referenced by pcl::VoxelGridCovariance< PointTarget >::filter(), pcl::VoxelGridCovariance< PointTarget >::nearestKSearch(), and pcl::VoxelGridCovariance< PointTarget >::radiusSearch().
|
protected |
Point cloud containing centroids of voxels containing atleast minimum number of points.
Definition at line 533 of file voxel_grid_covariance.h.
Referenced by pcl::VoxelGridCovariance< PointTarget >::filter(), and pcl::VoxelGridCovariance< PointTarget >::getCentroids().
|
protected |
Indices of leaf structurs associated with each point in voxel_centroids_ (used for searching).
Definition at line 536 of file voxel_grid_covariance.h.
Referenced by pcl::VoxelGridCovariance< PointTarget >::nearestKSearch(), and pcl::VoxelGridCovariance< PointTarget >::radiusSearch().