目录
-
- 经纬线扫描法
- 网格划分法
- 法线估计法
经纬线扫描法 经纬线扫描法的基本思想是:将经过坐标变换后的二维数据点集按照 x值的大小排序后存储在一个链表中,在二维平面建立点集的最小包围盒并分别计算出 x 和 y 的最大、最小值;令经线从 x 的最小值开始,取步长为dx,在 x 的取值范围内分别计算出每根经线的最大和最小 y 值,并将它们的索引值放在一个新建的链表中,扫描完整个 x 区间;同样的方法扫描纬线,最后将重复的索引值删掉。
下面代码在点云主法线方向和z轴夹具较小时表现较好,其他情况需要修改。
#include
#include
#include #include void BoundaryExtraction(pcl::PointCloud::Ptr cloud, pcl::PointCloud::Ptr cloud_boundary, int resolution)
{
pcl::PointXYZ px_min = *std::min_element(cloud->begin(), cloud->end(), [](pcl::PointXYZ pt1, pcl::PointXYZ pt2) {return pt1.x < pt2.x;
});
pcl::PointXYZ px_max = *std::max_element(cloud->begin(), cloud->end(), [](pcl::PointXYZ pt1, pcl::PointXYZ pt2) {return pt1.x < pt2.x;
});
float delta_x = (px_max.x - px_min.x) / resolution;
float min_y = INT_MAX, max_y = -INT_MAX;
std::vector indexs_x(2 * resolution);
std::vector::pair> minmax_x(resolution, { INT_MAX,-INT_MAX });
for (size_t i = 0;
i < cloud->size();
++i)
{
int id = (cloud->points[i].x - px_min.x) / delta_x;
if (cloud->points[i].y < minmax_x[id].first)
{
minmax_x[id].first = cloud->points[i].y;
indexs_x[id] = i;
}
else if (cloud->points[i].y > minmax_x[id].second)
{
minmax_x[id].second = cloud->points[i].y;
indexs_x[id + resolution] = i;
}
} pcl::PointXYZ py_min = *std::min_element(cloud->begin(), cloud->end(), [](pcl::PointXYZ pt1, pcl::PointXYZ pt2) {return pt1.y < pt2.y;
});
pcl::PointXYZ py_max = *std::max_element(cloud->begin(), cloud->end(), [](pcl::PointXYZ pt1, pcl::PointXYZ pt2) {return pt1.y < pt2.y;
});
float delta_y = (py_max.y - py_min.y) / resolution;
float min_x = INT_MAX, max_x = -INT_MAX;
std::vector indexs_y(2 * resolution);
std::vector::pair> minmax_y(resolution, { INT_MAX,-INT_MAX });
for (size_t i = 0;
i < cloud->size();
++i)
{
int id = (cloud->points[i].y - py_min.y) / delta_y;
if (cloud->points[i].x < minmax_y[id].first)
{
minmax_y[id].first = cloud->points[i].x;
indexs_y[id] = i;
}
else if (cloud->points[i].x > minmax_y[id].second)
{
minmax_y[id].second = cloud->points[i].x;
indexs_y[id + resolution] = i;
}
} pcl::PointCloud::Ptr cloud_xboundary(new pcl::PointCloud);
pcl::copyPointCloud(*cloud, indexs_x, *cloud_xboundary);
pcl::PointCloud::Ptr cloud_yboundary(new pcl::PointCloud);
pcl::copyPointCloud(*cloud, indexs_y, *cloud_yboundary);
*cloud_boundary = *cloud_xboundary + *cloud_yboundary;
}int main(int argc, char** argv)
{
clock_t start = clock();
pcl::PointCloud::Ptr cloud(new pcl::PointCloud), cloud_boundary(new pcl::PointCloud);
pcl::io::loadPCDFile("test.pcd", *cloud);
BoundaryExtraction(cloud, cloud_boundary, 200);
clock_t stop = clock();
double endtime = (double)(stop - start) / CLOCKS_PER_SEC;
std::cout << "time:" << endtime * 1000 << "ms" << std::endl;
pcl::io::savePCDFileBinary("boundary.pcd", *cloud_boundary);
system("pause");
return 0;
}
网格划分法 网格划分法分为三个步骤:(1)网格划分(2)寻找边界网格(3)提取边界线。首先建立数据点集的最小包围盒,并用给定间隔的矩形网格将其分割;然后找出边界网格,将这些边界网格按顺序连接起来形成一条由边界网格组成的“粗边界”;再对每个边界网格按照某种规则判断其内的点是否为边界点,连接初始边界,并对此边界线进一步处理使其光滑。
文章图片
文章图片
#include
#include
#include #include #include typedef pcl::PointCloud PointCloud;
void BoundaryExtraction(PointCloud::Ptr cloud, PointCloud::Ptr cloud_boundary, int resolution)
{
pcl::PointXYZ px_min = *std::min_element(cloud->begin(), cloud->end(), [](pcl::PointXYZ pt1, pcl::PointXYZ pt2) {return pt1.x < pt2.x;
});
pcl::PointXYZ px_max = *std::max_element(cloud->begin(), cloud->end(), [](pcl::PointXYZ pt1, pcl::PointXYZ pt2) {return pt1.x < pt2.x;
});
pcl::PointXYZ py_min = *std::min_element(cloud->begin(), cloud->end(), [](pcl::PointXYZ pt1, pcl::PointXYZ pt2) {return pt1.y < pt2.y;
});
pcl::PointXYZ py_max = *std::max_element(cloud->begin(), cloud->end(), [](pcl::PointXYZ pt1, pcl::PointXYZ pt2) {return pt1.y < pt2.y;
});
float x_min = px_min.x, x_max = px_max.x, y_min = py_min.y, y_max = py_max.y;
float L = sqrt((x_max - x_min)*(y_max - y_min) / resolution);
int x_num = (x_max - x_min) / L + 1;
int y_num = (y_max - y_min) / L + 1;
//std::cout << L << " " << x_num << " " << y_num << std::endl;
std::vector::vector> uv(x_num + 1, std::vector(y_num + 1));
for (int i = 0;
i <= x_num;
++i)
{
for (int j = 0;
j <= y_num;
++j)
{
PointCloud::Ptr ptcloud(new PointCloud);
uv[i][j] = ptcloud;
}
}
for (int i = 0;
i < cloud->size();
++i)
{
int x_id = (cloud->points[i].x - x_min) / L;
int y_id = (cloud->points[i].y - y_min) / L;
uv[x_id][y_id]->push_back(cloud->points[i]);
} std::vector::vector> boundary_index(x_num + 1, std::vector(y_num + 1, false));
for (int i = 0;
i <= x_num;
++i)
{
if (uv[i][0]->size())
boundary_index[i][0] = true;
if (uv[i][y_num]->size())
boundary_index[i][y_num] = true;
}
for (int i = 0;
i <= y_num;
++i)
{
if(uv[0][i]->size())
boundary_index[0][i] = true;
if (uv[x_num][i]->size())
boundary_index[x_num][i] = true;
}
for (int i = 1;
i < x_num-1;
++i)
{
for (int j = 1;
j < y_num-1;
++j)
{
if (uv[i][j]->size())
{
if (!uv[i - 1][j - 1]->size() || !uv[i][j - 1]->size() || !uv[i + 1][j - 1]->size() || !uv[i][j - 1]->size() ||
!uv[i + 1][j - 1]->size() || !uv[i + 1][j]->size() || !uv[i + 1][j + 1]->size() || !uv[i][j + 1]->size())
boundary_index[i][j] = true;
}
}
} for (int i = 0;
i <= x_num;
++i)
{
for (int j = 0;
j <= y_num;
++j)
{
//std::cout << i << " " << j << " " << uv[i][j]->points.size() << std::endl;
if (boundary_index[i][j])
{
PointCloud::Ptr ptcloud(new PointCloud);
ptcloud = uv[i][j];
Eigen::Vector4f cloud_centroid;
pcl::compute3DCentroid(*ptcloud, cloud_centroid);
cloud_boundary->push_back(pcl::PointXYZ(cloud_centroid(0), cloud_centroid(1), cloud_centroid(2)));
}
}
}
}int main(int argc, char** argv)
{
clock_t start = clock();
PointCloud::Ptr cloud(new PointCloud), cloud_boundary(new PointCloud);
pcl::io::loadPCDFile("4icp5+6+icp_skeleton.pcd", *cloud);
BoundaryExtraction(cloud, cloud_boundary, 200*200);
clock_t stop = clock();
double endtime = (double)(stop - start) / CLOCKS_PER_SEC;
std::cout << "time:" << endtime * 1000 << "ms" << std::endl;
pcl::io::savePCDFile("boundary.pcd", *cloud_boundary);
system("pause");
return 0;
}
法线估计法 可参考PCL:点云数据基于法线的边界提取(从最初的法线估计理论推导到最终的边界提取)
#include
#include
#include
#include
#include #include #include #include #include #include #include #include #include #include #include using namespace std;
int main(int argc, char **argv)
{
clock_t start = clock();
pcl::PointCloud::Ptr cloud(new pcl::PointCloud);
if (pcl::io::loadPCDFile(argv[1], *cloud) == -1)
{
PCL_ERROR("COULD NOT READ FILE. \n");
return (-1);
}
//std::cout << "points size is:" << cloud->size() << std::endl;
pcl::VoxelGrid voxel_grid;
voxel_grid.setLeafSize(std::stof(argv[2]), std::stof(argv[2]), std::stof(argv[2]));
voxel_grid.setInputCloud(cloud);
pcl::PointCloud::Ptr cloud_filtered(new pcl::PointCloud);
voxel_grid.filter(*cloud_filtered);
//std::cout << "filtered points size is:" << cloud_filtered->size() << std::endl;
pcl::PointCloud::Ptr normals(new pcl::PointCloud);
pcl::PointCloud boundaries;
pcl::BoundaryEstimation est;
pcl::search::KdTree::Ptr tree(new pcl::search::KdTree());
//pcl::NormalEstimation normEst;
//其中pcl::PointXYZ表示输入类型数据,pcl::Normal表示输出类型,且pcl::Normal前三项是法向,最后一项是曲率
pcl::NormalEstimationOMP normEst;
normEst.setNumberOfThreads(12);
// 手动设置线程数,否则提示错误
normEst.setInputCloud(cloud_filtered);
normEst.setSearchMethod(tree);
normEst.setRadiusSearch(std::stof(argv[3]));
//法向估计的半径
//normEst.setKSearch(9);
//法向估计的点数
normEst.compute(*normals);
//cout << "normal size is " << normals->size() << endl;
est.setInputCloud(cloud_filtered);
est.setInputNormals(normals);
est.setSearchMethod(tree);
est.setKSearch(500);
//一般这里的数值越高,最终边界识别的精度越好
est.compute(boundaries);
pcl::PointCloud::Ptr boundPoints(new pcl::PointCloud);
pcl::PointCloud noBoundPoints;
int countBoundaries = 0;
for (int i = 0;
isize();
i++) {
uint8_t x = (boundaries.points[i].boundary_point);
int a = static_cast(x);
//该函数的功能是强制类型转换
if (a == 1)
{
(*boundPoints).push_back(cloud_filtered->points[i]);
countBoundaries++;
}
else
noBoundPoints.push_back(cloud_filtered->points[i]);
} clock_t stop = clock();
double endtime = (double)(stop - start) / CLOCKS_PER_SEC;
std::cout << "time:" << endtime * 1000 << "ms" << std::endl;
std::cout << "boundary size is:" << countBoundaries << std::endl;
//pcl::io::savePCDFileASCII("boundary.pcd", *boundPoints);
//pcl::io::savePCDFileASCII("NoBoundpoints.pcd", noBoundPoints);
pcl::visualization::CloudViewer viewer("boundary");
viewer.showCloud(boundPoints);
while (!viewer.wasStopped())
{
}
return 0;
}
【3D|点云边界提取方法总结】参考资料:点云的边界提取及角点检测算法研究
推荐阅读
- CV|2. vit——vision transformer
- 深度学习|yolov5安全帽检测、反光衣检测、抽烟检测
- 深度学习|关于添加注意力模块的yolov5-5.0与yolov5-6.0的检测效果对比
- 深度学习|yolov5中使用denselayer替换focus,fpn结构改为bi-fpn
- 深度学习|关于yolov5加注意力之后的yaml文件讲解(5.0版本和6.0版本通用),文末有一个大部分人都没注意到的细节
- Delphi|RAD Studio Delphi C++ Builder 2020年11月开发路线图PPT(研发Delphi WebAssembly编译器)
- 开发语言|C++ Builder与Visual C++孰优孰劣
- c++|通过预编译头文件的方法来提高c++builder的编译速度
- C++|C++ 编译