Apollo 10.0
自动驾驶开放平台
apollo::localization::ndt::VoxelGridCovariance< PointT > 模板类 参考

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

#include <ndt_voxel_grid_covariance.h>

apollo::localization::ndt::VoxelGridCovariance< PointT > 的协作图:

Public 成员函数

 VoxelGridCovariance ()
 Constructor.
 
void SetInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset.
 
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).
 
int GetMinPointPerVoxel ()
 Get the minimum number of points required for a cell to be used.
 
void filter (const std::vector< Leaf > &cell_leaf, bool searchable=true)
 Initializes voxel structure.
 
void SetMap (const std::vector< Leaf > &map_leaves, PointCloudPtr output)
 
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.
 
PointCloudPtr GetCentroids ()
 Get a pointcloud containing the voxel centroids.
 
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.
 
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 类型

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

Protected 属性

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.
 
std::map< size_t, Leafleaves_
 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 structurs associated with each point.
 
pcl::KdTreeFLANN< PointT > kdtree_
 KdTree generated using voxel_centroids_ (used for searching).
 
Eigen::Vector3d map_left_top_corner_
 Left top corner.
 

详细描述

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

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

在文件 ndt_voxel_grid_covariance.h103 行定义.

成员类型定义说明

◆ PointCloud

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

在文件 ndt_voxel_grid_covariance.h108 行定义.

◆ PointCloudConstPtr

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

在文件 ndt_voxel_grid_covariance.h110 行定义.

◆ PointCloudPtr

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

在文件 ndt_voxel_grid_covariance.h109 行定义.

构造及析构函数说明

◆ VoxelGridCovariance()

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

Constructor.

在文件 ndt_voxel_grid_covariance.h124 行定义.

126 leaves_(),
129 kdtree_() {
130 leaf_size_.setZero();
131 min_b_.setZero();
132 max_b_.setZero();
133 }
pcl::KdTreeFLANN< PointT > kdtree_
KdTree generated using voxel_centroids_ (used for searching).
int min_points_per_voxel_
Minimum points contained with in a voxel to allow it to be usable.
std::vector< int > voxel_centroids_leaf_indices_
Indices of leaf structurs associated with each point.
PointCloudPtr voxel_centroids_
Point cloud containing centroids of voxels containing at least minimum number of points.
std::map< size_t, Leaf > leaves_
Voxel structure containing all leaf nodes (includes voxels with less than a sufficient number of poin...

成员函数说明

◆ filter()

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

Initializes voxel structure.

在文件 ndt_voxel_grid_covariance.h154 行定义.

155 {
157 SetMap(cell_leaf, voxel_centroids_);
158 if (voxel_centroids_->size() > 0) {
159 kdtree_.setInputCloud(voxel_centroids_);
160 }
161 }
void SetMap(const std::vector< Leaf > &map_leaves, PointCloudPtr output)

◆ GetCentroids()

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

Get a pointcloud containing the voxel centroids.

在文件 ndt_voxel_grid_covariance.h235 行定义.

235{ return 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 ( Eigen::Vector3f *  p)
inline

Get the voxel containing point p.

  • 返回
    const pointer to leaf structure

在文件 ndt_voxel_grid_covariance.h206 行定义.

206 {
207 // Generate index associated with p
208 int ijk0 = static_cast<int>((p->x() - map_left_top_corner_(0)) *
210 min_b_[0];
211 int ijk1 = static_cast<int>((p->y() - map_left_top_corner_(1)) *
213 min_b_[1];
214 int ijk2 = static_cast<int>((p->z() - map_left_top_corner_(2)) *
216 min_b_[2];
217
218 // Compute the centroid leaf index
219 int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
220
221 // Find leaf associated with index
222 typename std::map<size_t, Leaf>::iterator leaf_iter = leaves_.find(idx);
223 if (leaf_iter == leaves_.end()) {
224 return nullptr;
225 }
226 // If such a leaf exists return the pointer to the leaf structure
227 LeafConstPtr ret(&(leaf_iter->second));
228 return ret;
229 }
const Leaf * LeafConstPtr
Const pointer to VoxelGridCovariance leaf structure

◆ GetLeaf() [2/3]

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

Get the voxel containing point p.

在文件 ndt_voxel_grid_covariance.h166 行定义.

166 {
167 typename std::map<size_t, Leaf>::iterator leaf_iter = leaves_.find(index);
168 if (leaf_iter == leaves_.end()) {
169 return nullptr;
170 }
171 LeafConstPtr ret(&(leaf_iter->second));
172 return ret;
173 }

◆ GetLeaf() [3/3]

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

Get the voxel containing point p.

参数
[in]pthe point to get the leaf structure at
返回
const pointer to leaf structure

在文件 ndt_voxel_grid_covariance.h179 行定义.

179 {
180 // Generate index associated with p
181 int ijk0 = static_cast<int>((p->x - map_left_top_corner_(0)) *
183 min_b_[0];
184 int ijk1 = static_cast<int>((p->y - map_left_top_corner_(1)) *
186 min_b_[1];
187 int ijk2 = static_cast<int>((p->z - map_left_top_corner_(2)) *
189 min_b_[2];
190
191 // Compute the centroid leaf index
192 int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
193
194 // Find leaf associated with index
195 typename std::map<size_t, Leaf>::iterator leaf_iter = leaves_.find(idx);
196 if (leaf_iter == leaves_.end()) {
197 return nullptr;
198 }
199 // If such a leaf exists return the pointer to the leaf structure
200 LeafConstPtr ret(&(leaf_iter->second));
201 return ret;
202 }

◆ GetLeaves()

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

Get the leaf structure map.

在文件 ndt_voxel_grid_covariance.h232 行定义.

232{ return leaves_; }

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

在文件 ndt_voxel_grid_covariance.h151 行定义.

151{ return min_points_per_voxel_; }

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

在文件 ndt_voxel_grid_covariance.h136 行定义.

◆ 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

在文件 ndt_voxel_grid_covariance.h246 行定义.

246 {
247 map_left_top_corner_ = left_top_corner;
248 }

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

在文件 ndt_voxel_grid_covariance.h140 行定义.

140 {
141 if (min_points_per_voxel > 2) {
142 min_points_per_voxel_ = min_points_per_voxel;
143 } else {
144 AWARN << "Covariance calculation requires at least 3 "
145 << "points, setting Min Point per Voxel to 3 ";
147 }
148 }
#define AWARN
Definition log.h:43

◆ SetVoxelGridResolution()

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

在文件 ndt_voxel_grid_covariance.h250 行定义.

250 {
251 leaf_size_[0] = lx;
252 leaf_size_[1] = ly;
253 leaf_size_[2] = lz;
254 // Avoid division errors
255 if (leaf_size_[3] == 0) {
256 leaf_size_[3] = 1;
257 } // Use multiplications instead of divisions
258 inverse_leaf_size_ = Eigen::Array4f::Ones() / leaf_size_.array();
259 }

类成员变量说明

◆ div_b_

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

在文件 ndt_voxel_grid_covariance.h119 行定义.

◆ divb_mul_

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

在文件 ndt_voxel_grid_covariance.h120 行定义.

◆ input_

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

在文件 ndt_voxel_grid_covariance.h111 行定义.

◆ inverse_leaf_size_

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

在文件 ndt_voxel_grid_covariance.h114 行定义.

◆ kdtree_

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

KdTree generated using voxel_centroids_ (used for searching).

在文件 ndt_voxel_grid_covariance.h278 行定义.

◆ leaf_size_

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

在文件 ndt_voxel_grid_covariance.h113 行定义.

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

在文件 ndt_voxel_grid_covariance.h268 行定义.

◆ map_left_top_corner_

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

Left top corner.

在文件 ndt_voxel_grid_covariance.h281 行定义.

◆ max_b_

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

在文件 ndt_voxel_grid_covariance.h117 行定义.

◆ min_b_

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

在文件 ndt_voxel_grid_covariance.h116 行定义.

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

在文件 ndt_voxel_grid_covariance.h264 行定义.

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

在文件 ndt_voxel_grid_covariance.h272 行定义.

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

在文件 ndt_voxel_grid_covariance.h275 行定义.


该类的文档由以下文件生成: