Apollo  6.0
Open source self driving car software
Public Member Functions | Protected Types | Protected Attributes | List of all members
apollo::localization::ndt::VoxelGridCovariance< PointT > Class Template Reference

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

#include <ndt_voxel_grid_covariance.h>

Collaboration diagram for apollo::localization::ndt::VoxelGridCovariance< PointT >:
Collaboration graph

Public Member Functions

 VoxelGridCovariance ()
 Constructor. More...
 
void SetInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset. 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 filter (const std::vector< Leaf > &cell_leaf, bool searchable=true)
 Initializes voxel structure. More...
 
void SetMap (const std::vector< Leaf > &map_leaves, PointCloudPtr output)
 
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...
 
const std::map< size_t, Leaf > & GetLeaves ()
 Get the leaf structure map. More...
 
PointCloudPtr GetCentroids ()
 Get a pointcloud containing the voxel centroids. 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...
 
void GetDisplayCloud (pcl::PointCloud< pcl::PointXYZ > *cell_cloud)
 
void SetMapLeftTopCorner (const Eigen::Vector3d &left_top_corner)
 
void SetVoxelGridResolution (float lx, float ly, float lz)
 

Protected Types

typedef pcl::PointCloud< PointT > PointCloud
 
typedef boost::shared_ptr< PointCloudPointCloudPtr
 
typedef boost::shared_ptr< const PointCloudPointCloudConstPtr
 

Protected Attributes

PointCloudConstPtr input_
 
Eigen::Vector4f leaf_size_
 
Eigen::Array4f inverse_leaf_size_
 
Eigen::Vector4i min_b_
 
Eigen::Vector4i max_b_
 
Eigen::Vector4i div_b_
 
Eigen::Vector4i divb_mul_
 
int min_points_per_voxel_
 Minimum points contained with in a voxel to allow it to be usable. More...
 
std::map< size_t, Leafleaves_
 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 at least minimum number of points. More...
 
std::vector< int > voxel_centroids_leaf_indices_
 Indices of leaf structurs associated with each point. More...
 
pcl::KdTreeFLANN< PointT > kdtree_
 KdTree generated using voxel_centroids_ (used for searching). More...
 
Eigen::Vector3d map_left_top_corner_
 Left top corner. More...
 

Detailed Description

template<typename PointT>
class apollo::localization::ndt::VoxelGridCovariance< PointT >

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

Member Typedef Documentation

◆ PointCloud

template<typename PointT>
typedef pcl::PointCloud<PointT> apollo::localization::ndt::VoxelGridCovariance< PointT >::PointCloud
protected

◆ PointCloudConstPtr

template<typename PointT>
typedef boost::shared_ptr<const PointCloud> apollo::localization::ndt::VoxelGridCovariance< PointT >::PointCloudConstPtr
protected

◆ PointCloudPtr

template<typename PointT>
typedef boost::shared_ptr<PointCloud> apollo::localization::ndt::VoxelGridCovariance< PointT >::PointCloudPtr
protected

Constructor & Destructor Documentation

◆ VoxelGridCovariance()

template<typename PointT>
apollo::localization::ndt::VoxelGridCovariance< PointT >::VoxelGridCovariance ( )
inline

Constructor.

Member Function Documentation

◆ filter()

template<typename PointT>
void apollo::localization::ndt::VoxelGridCovariance< PointT >::filter ( const std::vector< Leaf > &  cell_leaf,
bool  searchable = true 
)
inline

Initializes voxel structure.

◆ GetCentroids()

template<typename PointT>
PointCloudPtr apollo::localization::ndt::VoxelGridCovariance< PointT >::GetCentroids ( )
inline

Get a pointcloud containing the voxel centroids.

◆ GetDisplayCloud()

template<typename PointT>
void apollo::localization::ndt::VoxelGridCovariance< PointT >::GetDisplayCloud ( pcl::PointCloud< pcl::PointXYZ > *  cell_cloud)

◆ GetLeaf() [1/3]

template<typename PointT>
LeafConstPtr apollo::localization::ndt::VoxelGridCovariance< PointT >::GetLeaf ( int  index)
inline

Get the voxel containing point p.

◆ GetLeaf() [2/3]

template<typename PointT>
LeafConstPtr apollo::localization::ndt::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

◆ GetLeaf() [3/3]

template<typename PointT>
LeafConstPtr apollo::localization::ndt::VoxelGridCovariance< PointT >::GetLeaf ( Eigen::Vector3f *  p)
inline

Get the voxel containing point p.*.

Returns
const pointer to leaf structure

◆ GetLeaves()

template<typename PointT>
const std::map<size_t, Leaf>& apollo::localization::ndt::VoxelGridCovariance< PointT >::GetLeaves ( )
inline

Get the leaf structure map.

◆ GetMinPointPerVoxel()

template<typename PointT>
int apollo::localization::ndt::VoxelGridCovariance< PointT >::GetMinPointPerVoxel ( )
inline

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

◆ RadiusSearch()

template<typename PointT>
int apollo::localization::ndt::VoxelGridCovariance< PointT >::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.

◆ SetInputCloud()

template<typename PointT>
void apollo::localization::ndt::VoxelGridCovariance< PointT >::SetInputCloud ( const PointCloudConstPtr cloud)
inline

Provide a pointer to the input dataset.

◆ SetMap()

template<typename PointT>
void apollo::localization::ndt::VoxelGridCovariance< PointT >::SetMap ( const std::vector< Leaf > &  map_leaves,
PointCloudPtr  output 
)

◆ SetMapLeftTopCorner()

template<typename PointT>
void apollo::localization::ndt::VoxelGridCovariance< PointT >::SetMapLeftTopCorner ( const Eigen::Vector3d &  left_top_corner)
inline

◆ SetMinPointPerVoxel()

template<typename PointT>
void apollo::localization::ndt::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).

◆ SetVoxelGridResolution()

template<typename PointT>
void apollo::localization::ndt::VoxelGridCovariance< PointT >::SetVoxelGridResolution ( float  lx,
float  ly,
float  lz 
)
inline

Member Data Documentation

◆ div_b_

template<typename PointT>
Eigen::Vector4i apollo::localization::ndt::VoxelGridCovariance< PointT >::div_b_
protected

◆ divb_mul_

template<typename PointT>
Eigen::Vector4i apollo::localization::ndt::VoxelGridCovariance< PointT >::divb_mul_
protected

◆ input_

template<typename PointT>
PointCloudConstPtr apollo::localization::ndt::VoxelGridCovariance< PointT >::input_
protected

◆ inverse_leaf_size_

template<typename PointT>
Eigen::Array4f apollo::localization::ndt::VoxelGridCovariance< PointT >::inverse_leaf_size_
protected

◆ kdtree_

template<typename PointT>
pcl::KdTreeFLANN<PointT> apollo::localization::ndt::VoxelGridCovariance< PointT >::kdtree_
protected

KdTree generated using voxel_centroids_ (used for searching).

◆ leaf_size_

template<typename PointT>
Eigen::Vector4f apollo::localization::ndt::VoxelGridCovariance< PointT >::leaf_size_
protected

◆ leaves_

template<typename PointT>
std::map<size_t, Leaf> apollo::localization::ndt::VoxelGridCovariance< PointT >::leaves_
protected

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

◆ map_left_top_corner_

template<typename PointT>
Eigen::Vector3d apollo::localization::ndt::VoxelGridCovariance< PointT >::map_left_top_corner_
protected

Left top corner.

◆ max_b_

template<typename PointT>
Eigen::Vector4i apollo::localization::ndt::VoxelGridCovariance< PointT >::max_b_
protected

◆ min_b_

template<typename PointT>
Eigen::Vector4i apollo::localization::ndt::VoxelGridCovariance< PointT >::min_b_
protected

◆ min_points_per_voxel_

template<typename PointT>
int apollo::localization::ndt::VoxelGridCovariance< PointT >::min_points_per_voxel_
protected

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

◆ voxel_centroids_

template<typename PointT>
PointCloudPtr apollo::localization::ndt::VoxelGridCovariance< PointT >::voxel_centroids_
protected

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

◆ voxel_centroids_leaf_indices_

template<typename PointT>
std::vector<int> apollo::localization::ndt::VoxelGridCovariance< PointT >::voxel_centroids_leaf_indices_
protected

Indices of leaf structurs associated with each point.


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