Template Class VoxelGridCovariance

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public pcl::VoxelGrid< PointT >

Class Documentation

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

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

Author

Brian Okorn (Space and Naval Warfare Systems Center Pacific)

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

Public Types

typedef pcl::shared_ptr<pcl::VoxelGrid<PointT>> Ptr
typedef pcl::shared_ptr<const pcl::VoxelGrid<PointT>> ConstPtr
typedef Leaf *LeafPtr

Pointer to VoxelGridCovariance leaf structure.

typedef const Leaf *LeafConstPtr

Const pointer to VoxelGridCovariance leaf structure.

typedef std::map<size_t, Leaf> Map

Public Functions

inline VoxelGridCovariance()

Constructor. Sets leaf_size_ to 0 and searchable_ to false.

inline 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).

Parameters:

min_points_per_voxel[in] the minimum number of points for required for a voxel to be used

inline int getMinPointPerVoxel()

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

inline void setCovEigValueInflationRatio(double min_covar_eigvalue_mult)

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

Parameters:

min_covar_eigvalue_mult[in] the minimum allowable ratio between eigenvalues

inline double getCovEigValueInflationRatio()

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

Returns:

the minimum allowable ratio between eigenvalues

inline void filter(PointCloud &output, bool searchable = false)

Filter cloud and initializes voxel structure.

Parameters:
  • output[out] cloud containing centroids of voxels containing a sufficient number of points

  • searchable[in] flag if voxel structure is searchable, if true then kdtree is built

inline void filter(bool searchable = false)

Initializes voxel structure.

Parameters:

searchable[in] flag if voxel structure is searchable, if true then kdtree is built

inline LeafConstPtr getLeaf(int index)

Get the voxel containing point p.

Parameters:

index[in] the index of the leaf structure node

Returns:

const pointer to leaf structure

inline LeafConstPtr getLeaf(PointT &p)

Get the voxel containing point p.

Parameters:

p[in] the point to get the leaf structure at

Returns:

const pointer to leaf structure

inline LeafConstPtr getLeaf(Eigen::Vector3f &p)

Get the voxel containing point p.

Parameters:

p[in] the point to get the leaf structure at

Returns:

const pointer to leaf structure

int getNeighborhoodAtPoint(const Eigen::MatrixXi&, const PointT &reference_point, std::vector<LeafConstPtr> &neighbors) const

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

Note

Only voxels containing a sufficient number of points are used (slower than radius search in practice).

Parameters:
  • reference_point[in] the point to get the leaf structure at

  • neighbors[out]

Returns:

number of neighbors found

int getNeighborhoodAtPoint(const PointT &reference_point, std::vector<LeafConstPtr> &neighbors) const
int getNeighborhoodAtPoint7(const PointT &reference_point, std::vector<LeafConstPtr> &neighbors) const
int getNeighborhoodAtPoint1(const PointT &reference_point, std::vector<LeafConstPtr> &neighbors) const
inline const Map &getLeaves()

Get the leaf structure map.

Returns:

a map containing all leaves

inline PointCloudPtr getCentroids()

Get a pointcloud containing the voxel centroids.

Note

Only voxels containing a sufficient number of points are used.

Returns:

a map containing all leaves

void getDisplayCloud(pcl::PointCloud<pcl::PointXYZ> &cell_cloud)

Get a cloud to visualize each voxels normal distribution.

Parameters:

cell_cloud[out] a cloud created by sampling the normal distributions of each voxel

inline 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.

Note

Only voxels containing a sufficient number of points are used.

Parameters:
  • point[in] the given query point

  • k[in] the number of neighbors to search for

  • k_leaves[out] the resultant leaves of the neighboring points

  • k_sqr_distances[out] the resultant squared distances to the neighboring points

Returns:

number of neighbors found

inline 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.

Note

Only voxels containing a sufficient number of points are used.

Parameters:
  • cloud[in] the given query point

  • index[in] the index

  • k[in] the number of neighbors to search for

  • k_leaves[out] the resultant leaves of the neighboring points

  • k_sqr_distances[out] the resultant squared distances to the neighboring points

Returns:

number of neighbors found

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

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:
  • point[in] the given query point

  • radius[in] the radius of the sphere bounding all of p_q’s neighbors

  • k_leaves[out] the resultant leaves of the neighboring points

  • k_sqr_distances[out] the resultant squared distances to the neighboring points

  • max_nn[in]

Returns:

number of neighbors found

inline 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) const

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:
  • cloud[in] the given query point

  • index[in] a valid index in cloud representing a valid (i.e., finite) query point

  • radius[in] the radius of the sphere bounding all of p_q’s neighbors

  • k_leaves[out] the resultant leaves of the neighboring points

  • k_sqr_distances[out] the resultant squared distances to the neighboring points

  • max_nn[in]

Returns:

number of neighbors found

Protected Types

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

Protected Functions

void applyFilter(PointCloud &output)

Filter cloud and initializes voxel structure.

Parameters:

output[out] cloud containing centroids of voxels containing a sufficient number of points

Protected Attributes

bool searchable_

Flag to determine if voxel structure is searchable.

int min_points_per_voxel_

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

double min_covar_eigvalue_mult_

Minimum allowable ratio between eigenvalues to prevent singular covariance matrices.

Map leaves_

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

PointCloudPtr voxel_centroids_

Point cloud containing centroids of voxels containing at least minimum number of points.

std::vector<int> voxel_centroids_leaf_indices_

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

pcl::KdTreeFLANN<PointT> kdtree_

KdTree generated using voxel_centroids_ (used for searching).

struct Leaf

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

Public Functions

inline Leaf()

Constructor. Sets nr_points, icov_, mean_ and evals_ to 0 and cov_ and evecs_ to the identity matrix.

inline Eigen::Matrix3d getCov() const

Get the voxel covariance.

Returns:

covariance matrix

inline Eigen::Matrix3d getInverseCov() const

Get the inverse of the voxel covariance.

Returns:

inverse covariance matrix

inline Eigen::Vector3d getMean() const

Get the voxel centroid.

Returns:

centroid

inline Eigen::Matrix3d getEvecs() const

Get the eigen vectors of the voxel covariance.

Note

Order corresponds with getEvals

Returns:

matrix whose columns contain eigen vectors

inline Eigen::Vector3d getEvals() const

Get the eigen values of the voxel covariance.

Note

Order corresponds with getEvecs

Returns:

vector of eigen values

inline int getPointCount() const

Get the number of points contained by this voxel.

Returns:

number of points

Public Members

int nr_points

Number of points contained by voxel.

Eigen::Vector3d mean_

3D voxel centroid

Eigen::VectorXf centroid

Nd voxel centroid.

Note

Differs from mean_ when color data is used

Eigen::Matrix3d cov_

Voxel covariance matrix.

Eigen::Matrix3d icov_

Inverse of voxel covariance matrix.

Eigen::Matrix3d evecs_

Eigen vectors of voxel covariance matrix.

Eigen::Vector3d evals_

Eigen values of voxel covariance matrix.