pcl源码分析之计算ISS描述子(一)
文章目录
- 前言
- 一、应用案例
- 二、源码分析
- 1.ISSKeypoint3D类
- 2.compute函数
- 3.detectKeypoints 函数
- 总结
前言
ISS特征提取(Intrinsic Shape Signatures),是一种用于三维形状分析的局部特征描述子,在计算机视觉领域广泛应用。该方法通过检测具有显著几何特性的点来构建稳定的特征表示。
一、应用案例
#include <pcl/keypoints/iss_3d.h>
pcl::ISSKeypoint3D<pcl::PointXYZ, pcl::PointXYZ> iss;
pcl::PointCloud<pcl::PointXYZ>::Ptr keypoints(
new pcl::PointCloud<pcl::PointXYZ>());
pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(
new pcl::search::KdTree<pcl::PointXYZ>());
iss.setInputCloud(cloud_in);
iss.setSearchMethod(tree);
iss.setNumberOfThreads(4); // 初始化调度器并设置要使用的线程数
iss.setSalientRadius(0.3f); // 设置用于计算协方差矩阵的球邻域半径
iss.setNonMaxRadius(0.01f); // 设置非极大值抑制应用算法的半径
iss.setThreshold21(0.99); // 设定第二个和第一个特征值之比的上限
iss.setThreshold32(0.99); // 设定第三个和第二个特征值之比的上限
iss.setMinNeighbors(4); // 在应用非极大值抑制算法时,设置必须找到的最小邻居数
iss.compute(*keypoints);//输出ISS特征
二、源码分析
1.ISSKeypoint3D类
template <typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
class ISSKeypoint3D : public Keypoint<PointInT, PointOutT>
{
public:
//构造函数里定义了一些变量得初始值
ISSKeypoint3D (double salient_radius = 0.0001)
: salient_radius_ (salient_radius)
, non_max_radius_ (0.0)
, normal_radius_ (0.0)
, border_radius_ (0.0)
, gamma_21_ (0.975)
, gamma_32_ (0.975)
, third_eigen_value_ (0)
, edge_points_ (0)
, min_neighbors_ (5)
, normals_ (new pcl::PointCloud<NormalT>)
, angle_threshold_ (static_cast<float> (M_PI) / 2.0f)
, threads_ (0)
{
name_ = "ISSKeypoint3D";
search_radius_ = salient_radius_;
}
//上述应用实例中,基本的接口都在这里定义
//但是,compute函数却是继承了Keypoint类里的接口
...
protected:
...
//该函数在Keypoint类里定义了一个虚函数,在ISSKeypoint3D类中进行了具体的实现
void
detectKeypoints (PointCloudOut &output);
...
}
2.compute函数
template <typename PointInT, typename PointOutT> inline void
pcl::Keypoint<PointInT, PointOutT>::compute (PointCloudOut &output)
{
//初始化,原理之前讲过,在此不再赘述
if (!initCompute ())
{
PCL_ERROR ("[pcl::%s::compute] initCompute failed!\n", getClassName ().c_str ());
return;
}
// Perform the actual computation
//该函数是主要接口
detectKeypoints (output);
//继承PCLBase类
deinitCompute ();
// Reset the surface
if (input_ == surface_)
surface_.reset ();
}
3.detectKeypoints 函数
提取ISS特征点的原理,可以参考这两篇博文:文章1,文章2,结合起来看,才能成为自己的东西~~
template<typename PointInT, typename PointOutT, typename NormalT> void
pcl::ISSKeypoint3D<PointInT, PointOutT, NormalT>::detectKeypoints (PointCloudOut &output)
{
// Make sure the output cloud is empty
output.clear ();
//只有当border_radius_ 大于0时,才会进行点云边缘检测
if (border_radius_ > 0.0)
edge_points_ = getBoundaryPoints (*(input_->makeShared ()), border_radius_, angle_threshold_);
//这里和edge_points_ 一样,典型的c语言风格
//其实可以这样的:std::vector<bool> borders(input_->size(), false);
bool* borders = new bool [input_->size()];
//已经有了edge_points_,为啥还要给borders 赋值同样的?
#pragma omp parallel for \//for循环多线程,前面已经讲过很多遍,不再赘述
default(none) \
shared(borders) \
num_threads(threads_)
for (int index = 0; index < static_cast<int>(input_->size ()); index++)
{
borders[index] = false;
PointInT current_point = (*input_)[index];
if ((border_radius_ > 0.0) && (pcl::isFinite(current_point)))
{
pcl::Indices nn_indices;
std::vector<float> nn_distances;
this->searchForNeighbors (index, border_radius_, nn_indices, nn_distances);
for (const auto &nn_index : nn_indices)
{
if (edge_points_[nn_index])
{
borders[index] = true;
break;
}
}
}
}
//如果定义了_OPENMP宏,创建一个大小为threads_的Eigen::Vector3d指针数组omp_mem。
#ifdef _OPENMP
auto *omp_mem = new Eigen::Vector3d[threads_];
//如果定义了_OPENMP宏,则遍历threads_个线程,并将每个线程对应的Eigen::Vector3d对象的值设置为零,
//否则创建一个单独的Eigen::Vector3d对象,并将其值设置为零。
for (std::size_t i = 0; i < threads_; i++)
omp_mem[i].setZero (3);
#else
auto *omp_mem = new Eigen::Vector3d[1];
omp_mem[0].setZero (3);
#endif
//这个位置也是典型的c语言风格,实际上目的就是为了保存每个点云的协方差矩阵的特征值(3个)
double *prg_local_mem = new double[input_->size () * 3];
double **prg_mem = new double * [input_->size ()];
for (std::size_t i = 0; i < input_->size (); i++)
prg_mem[i] = prg_local_mem + 3 * i;
#pragma omp parallel for \
default(none) \
shared(borders, omp_mem, prg_mem) \
num_threads(threads_)
for (int index = 0; index < static_cast<int> (input_->size ()); index++)
{
#ifdef _OPENMP
int tid = omp_get_thread_num ();
#else
int tid = 0;
#endif
PointInT current_point = (*input_)[index];
//如果是点云边缘并且不为nan或者无穷大
if ((!borders[index]) && pcl::isFinite(current_point))
{
//if the considered point is not a border point and the point is "finite", then compute the scatter matrix
Eigen::Matrix3d cov_m = Eigen::Matrix3d::Zero ();
//计算协方差矩阵
getScatterMatrix (static_cast<int> (index), cov_m);
//计算协方差矩阵的特征值
Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> solver (cov_m);
const double& e1c = solver.eigenvalues ()[2];//特征值最大值
const double& e2c = solver.eigenvalues ()[1];//特征值次大值
const double& e3c = solver.eigenvalues ()[0];//特征值最小值
//三个特征值为nan或者无穷大时,直接continue
if (!std::isfinite (e1c) || !std::isfinite (e2c) || !std::isfinite (e3c))
continue;
//最大特征值小于0,计算
if (e3c < 0)
{
PCL_WARN ("[pcl::%s::detectKeypoints] : The third eigenvalue is negative! Skipping the point with index %i.\n",
name_.c_str (), index);
continue;
}
omp_mem[tid][0] = e2c / e1c;// λ2/λ1
omp_mem[tid][1] = e3c / e2c;// λ3/λ2
omp_mem[tid][2] = e3c;// λ3
}
//这里可以知道prg_mem是一个n*3的二维数组,分别将上面三个值按照id顺序存入prg_mem中
for (Eigen::Index d = 0; d < omp_mem[tid].size (); d++)
prg_mem[index][d] = omp_mem[tid][d];
}
for (int index = 0; index < static_cast<int>(input_->size ()); index++)
{
// λ2/λ1 > gamma_21_ && λ3/λ2 > gamma_32_,则认为是ISS特征
//并且将prg_mem对应的第三个值(也即 λ3)存入third_eigen_value_中
if (!borders[index])
{
if ((prg_mem[index][0] < gamma_21_) && (prg_mem[index][1] < gamma_32_))
third_eigen_value_[index] = prg_mem[index][2];
}
}
//同样,这里C++风格是std::vector<bool> feat_max (input_->size(), false);
//这里对所有点做上标记,以便下面和近邻点对比,确定是不是最终的ISS特征
bool* feat_max = new bool [input_->size()];
#pragma omp parallel for \
default(none) \
shared(feat_max) \
num_threads(threads_)
for (int index = 0; index < static_cast<int>(input_->size ()); index++)
{
feat_max [index] = false;
PointInT current_point = (*input_)[index];
//确保 λ3 > 0 且不为nan或者无穷大
if ((third_eigen_value_[index] > 0.0) && (pcl::isFinite(current_point)))
{
pcl::Indices nn_indices;
std::vector<float> nn_distances;
int n_neighbors;
//搜寻该点的近邻点
this->searchForNeighbors (index, non_max_radius_, nn_indices, nn_distances);
//转int数据类型
n_neighbors = static_cast<int> (nn_indices.size ());
//确保近邻点最小个数大于阈值
if (n_neighbors >= min_neighbors_)
{
bool is_max = true;
//确保该点的λ3是比其近邻点的λ3都要大
//突然发现,确定是不是近邻点的最大值,我也是这么干的~~
for (const auto& j : nn_indices)
if (third_eigen_value_[index] < third_eigen_value_[j])
is_max = false;
if (is_max)
feat_max[index] = true;
}
}
}
#pragma omp parallel for \
default(none) \
shared(feat_max, output) \
num_threads(threads_)
for (int index = 0; index < static_cast<int>(input_->size ()); index++)
{
//如果已经做了标记为true(也即是最终的ISS特征点),则将该点输出
if (feat_max[index])
#pragma omp critical
{
PointOutT p;
p.getVector3fMap () = (*input_)[index].getVector3fMap ();
output.push_back(p);
keypoints_indices_->indices.push_back (index);
}
}
output.header = input_->header;
output.width = output.size ();
output.height = 1;
// Clear the contents of variables and arrays before the beginning of the next computation.
if (border_radius_ > 0.0)
normals_.reset (new pcl::PointCloud<NormalT>);
//释放内存,典型的c语言风格,如果不释放,就会出现bug,还是C++智能指针好使吧~~
delete[] borders;
delete[] prg_mem;
delete[] prg_local_mem;
delete[] feat_max;
delete[] omp_mem;
}
总结
总结了一下pcl里计算ISS描述子的源码,这里把主要流程和原理分析了一下,某些重要的函数及其原理下一篇再继续~~