PCL库中类 pcl::MinCutSegmentation实现基于最小割的分割算法,该算法将一副点云图像分割为两部分:前景点云(目标物体)和背景点云(剩余部分)。
算法主要思想:
切割有两个非常重要的因素,第一个是获得点与点之间的拓扑关系,也就是生成一张“图”。第二个是给图中的连线赋予合适的权值。
(1)构造图:
对于给定的输入点云,以输入点云的所有点为顶点,以及一个源点和一个汇点,构造一个最近临图形,图形的每个顶点与源点和汇点以边线相连,得到t-links;除了源点和汇点,每一个顶点与其最近临点相连,得到n-links。
连接算法如下:
(2)权值:
根据连接点的情况,边被分为三种情况,不同的边对应不同的权值,有三种权值:
其中,是点到物体期望中心的水平面距离,利用以下公式计算,
Radius可看成是物体的半径,小于该半径的点被看成是前景点,是一个水平面上的半径值,由用户输入。
最小割算法必须先由人为指定至少一个前景点,该前景点必须在待分割的目标物体上才行;该算法适用于多个物体水平排列的点云图像,它只能在水平方向将目标物体分割出来,默认分割后的图形中,白色为前景点,红色为背景点。
测试示例:
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
using namespace pcl::console;
int main(int argc, char** argv)
{
if (argc < 2)
{
std::cout << ".exe xx.pcd -bc 1 -fc 1.0 -nc 0 -cx 68.97 -cy -18.55 -cz 0.57 -s 0.25 -r 3.0433856 -non 14 -sw 0.5" << endl;
return 0;
}//如果输入参数小于1个,输出提示信息
time_t start, end, diff[5], option;
start = time(0);
int NumberOfNeighbours = 14;//设置默认参数
bool Bool_Cuting = false; //设置默认参数
float far_cuting = 1, near_cuting = 0, C_x = 0.071753, C_y = -0.309913, C_z = 1.603000, Sigma = 0.25, Radius = 0.8, SourceWeight = 0.5;//设置默认输入参数
pcl::PointCloud ::Ptr cloud(new pcl::PointCloud );// 创建一个PointCloud 共享指针并进行实例化
if (pcl::io::loadPCDFile (argv[1], *cloud) == -1)// 加载点云数据
{
std::cout << "Cloud reading failed." << std::endl;
return (-1);
}
parse_argument(argc, argv, "-bc", Bool_Cuting);
parse_argument(argc, argv, "-fc", far_cuting);
parse_argument(argc, argv, "-nc", near_cuting);
//初始化前景(目标)点云的中心点,对于分割结果影响最大
parse_argument(argc, argv, "-cx", C_x);
parse_argument(argc, argv, "-cy", C_y);
parse_argument(argc, argv, "-cz", C_z);
parse_argument(argc, argv, "-s", Sigma); //设置平滑成本的sigma值,该值越小,使得平滑代价会随着两个定点距离增加迅速减小
parse_argument(argc, argv, "-r", Radius);//设置背景惩罚的半径
parse_argument(argc, argv, "-non", NumberOfNeighbours);//设置算法构造图时需要查找的邻近点数目,设置的越大,图包含的n-links边越多,增加了计算时间,提升了分割的准确度
parse_argument(argc, argv, "-sw", SourceWeight); //设置前景惩罚权重,该值越大,使得分割为前景的概率越大
pcl::IndicesPtr indices(new std::vector ); //创建一组索引
if (Bool_Cuting) //判断是否需要直通滤波
{
pcl::PassThrough pass; //设置直通滤波器对象
pass.setInputCloud(cloud); //设置输入点云
pass.setFilterFieldName("z"); //设置指定过滤的维度
pass.setFilterLimits(near_cuting, far_cuting); //设置指定纬度过滤的范围
pass.filter(*indices); //执行滤波,保存滤波结果在上述索引中
}
pcl::MinCutSegmentation seg; //创建一个PointXYZRGB类型的区域生长分割对象
seg.setInputCloud(cloud); //设置输入点云
if (Bool_Cuting)seg.setIndices(indices); //设置输入点云的索引
pcl::PointCloud::Ptr foreground_points(new pcl::PointCloud());//创建一个PointCloud 共享指针并进行实例化
pcl::PointXYZ point;//定义中心点并赋值
point.x = C_x;
point.y = C_y;
point.z = C_z;
foreground_points->points.push_back(point);
seg.setForegroundPoints(foreground_points); //输入前景点云(目标物体)的中心点
seg.setSigma(Sigma); //设置平滑成本的Sigma值
seg.setRadius(Radius); //设置背景惩罚权重的半径
seg.setNumberOfNeighbours(NumberOfNeighbours);//设置临近点数目
seg.setSourceWeight(SourceWeight); //设置前景惩罚权重
std::vector clusters;
seg.extract(clusters);//获取分割的结果,分割结果保存在点云索引的向量中。
std::cout << "Maximum flow is " << seg.getMaxFlow() << std::endl;//计算并输出分割期间所计算出的流值
pcl::PointCloud ::Ptr colored_cloud = seg.getColoredCloud();//对前景点赋予红色,对背景点赋予白色。
pcl::visualization::PCLVisualizer viewer("最小割分割方法");
viewer.addPointCloud(colored_cloud);
viewer.addSphere(point, Radius, 122, 122, 0, "sphere");
viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_OPACITY, 0.2, "sphere");
while (!viewer.wasStopped())
{
viewer.spin();
}//进行可视化
return (0);
}
执行命令:
.\min_cut_segmentation.exe ..\..\source\min_cut_segmentation_tutorial.pcd -bc 1 -fc 1.0 -nc 0 -cx 68.97 -cy -18.55 -c
z 0.57 -s 0.25 -r 3.0433856 -non 14 -sw 0.8
可视化:
目标物体被分割出:
白色为前景点;红色为背景点;浅黄色球指示用户设置的中心和半径;