Parcourir la source

v0.7.4 增加叶片剔除功能(在boxcrop和降采样后实现)

chenhongjiang il y a 1 an
Parent
commit
fc603b8cec
5 fichiers modifiés avec 143 ajouts et 18 suppressions
  1. 2 1
      ReadMe.txt
  2. 3 3
      gcv_conf.yml
  3. 130 13
      grab_point_rs.cpp
  4. 7 0
      grab_point_rs.h
  5. 1 1
      graft_cv_api.cpp

+ 2 - 1
ReadMe.txt

@@ -88,4 +88,5 @@ v0.6.16 
 v0.7.0 支持多线程调用业务接口
 v0.7.1 增加voxelsize参数;修改茎密度最大值的1/3为最小茎密度的下限(原来为1/2,有些小苗识别不出来)
 v0.7.2 增加结果图片输出功能;日志增加image_id信息
-v0.7.3 修改抓取位置,提供茎节分叉的位置(以前提供可抓取的位置,避开茎节的点)
+v0.7.3 修改抓取位置,提供茎节分叉的位置(以前提供可抓取的位置,避开茎节的点)
+v0.7.4 增加叶片剔除功能(在boxcrop和降采样后实现)

+ 3 - 3
gcv_conf.yml

@@ -1,6 +1,6 @@
 %YAML:1.0
 conf_parameters:
-   image_show: 1
+   image_show: 0
    image_return: 1
    image_row_grid: 20
    image_col_grid: 100
@@ -79,13 +79,13 @@ conf_parameters:
    sc_grab_xmin: -200
    sc_grab_xmax: 200
    sc_grab_ymin: -45
-   sc_grab_ymax: -15
+   sc_grab_ymax: 0
    sc_grab_zmin: 300
    sc_grab_zmax: 400
    sc_grab_stem_diameter: 5.0
    sc_grab_y_opt: -20
    sc_grab_seedling_dist: 40.0
-   sc_grab_stem_min_pts: 30
+   sc_grab_stem_min_pts: 45
    sc_grab_voxel_size: 0.02
    
 

+ 130 - 13
grab_point_rs.cpp

@@ -19,6 +19,7 @@
 #include <pcl\common\common.h>
 #include <pcl\features\moment_of_inertia_estimation.h>
 #include <pcl\segmentation\sac_segmentation.h>
+#include <pcl\segmentation\extract_clusters.h>
 #include <math.h>
 
 #include "grab_point_rs.h"
@@ -59,6 +60,7 @@ namespace graft_cv {
 		int dtype,
 		const char* fn/* = 0*/)
 	{
+		//数据加载功能实现,并生成imageid,保存原始数据到文件
 		int rst = 0;
 		m_dtype = dtype;
 		//generate image id
@@ -111,6 +113,7 @@ namespace graft_cv {
 		PositionInfo& posinfo
 		)
 	{
+		// 抓取位置识别入口函数,实现整个抓取位置识别功能,返回抓取位置信息
 		// dtype == 0, scion
 		// dtype != 0, rootstock
 		// 输入,穗苗--0, 砧木--1
@@ -124,7 +127,7 @@ namespace graft_cv {
 			return 1;
 		}
 		////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-		//1 crop filter
+		//1 crop filter,剪裁需要的部分点云
 		if (m_pLogger) {
 			m_pLogger->INFO(m_pcdId + ": begin crop");
 		}
@@ -158,7 +161,7 @@ namespace graft_cv {
 			m_pLogger->INFO(m_pcdId + ": end crop");
 		}
 		////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-		//2 filtler with radius remove
+		//2 filtler with radius remove, 去除孤立点
 		if (m_pLogger) {
 			m_pLogger->INFO(m_pcdId + ": begin ror");
 		}
@@ -177,7 +180,9 @@ namespace graft_cv {
 		ror.filter(*cloud_ror);
 		if (m_pLogger) {
 			stringstream buff;
-			buff << m_pcdId <<": RadiusOutlierRemoval filtered point cloud " << cloud_ror->width * cloud_ror->height << " data points. param stem_radius="<<
+			buff << m_pcdId <<": RadiusOutlierRemoval filtered point cloud " 
+				<< cloud_ror->width * cloud_ror->height
+				<< " data points. param stem_radius="<<
 				stem_radius<<", nb_points="<< nb_points;
 			m_pLogger->INFO(buff.str());
 		}
@@ -192,25 +197,27 @@ namespace graft_cv {
 			m_pLogger->INFO(m_pcdId + ": end ror");
 		}
 		////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-		//3 voxel grid down sampling
+		//3 voxel grid down sampling, 降采样
 		if (m_pLogger) {
 			m_pLogger->INFO(m_pcdId + ": begin down");
 		}
-		pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_dowm_sampled(new pcl::PointCloud<pcl::PointXYZ>);
+		pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_dowm_sampled_with_leaf(new pcl::PointCloud<pcl::PointXYZ>);		
 		pcl::VoxelGrid<pcl::PointXYZ> outrem;
 		outrem.setInputCloud(cloud_ror);
 		//outrem.setLeafSize(stem_radius, stem_radius, stem_radius);
 		double voxel_size = m_cparam.rs_grab_voxel_size;
 		if (m_dtype == 0) { voxel_size = m_cparam.sc_grab_voxel_size; }
 		outrem.setLeafSize(voxel_size, voxel_size, voxel_size);
-		outrem.filter(*cloud_dowm_sampled);
+		outrem.filter(*cloud_dowm_sampled_with_leaf);
 
 		if (m_pLogger) {
 			stringstream buff;
-			buff << m_pcdId <<": VoxelGrid dowm_sampled point cloud " << cloud_dowm_sampled->width * cloud_dowm_sampled->height << " data points (if < 50, return)";
+			buff << m_pcdId <<": VoxelGrid dowm_sampled point cloud " 
+				<< cloud_dowm_sampled_with_leaf->width * cloud_dowm_sampled_with_leaf->height
+				<< " data points (if < 50, return)";
 			m_pLogger->INFO(buff.str());
 		}
-		if (cloud_dowm_sampled->width * cloud_dowm_sampled->height < 50) {
+		if (cloud_dowm_sampled_with_leaf->width * cloud_dowm_sampled_with_leaf->height < 50) {
 			return 1;
 		}
 
@@ -220,9 +227,23 @@ namespace graft_cv {
 		if (m_pLogger) {
 			m_pLogger->INFO(m_pcdId + ": end down");
 		}
-
 		////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-		//4 seedling position,找到第一个位置上的植株
+		// 4 对截取的点云进行聚类分析,剔除叶片
+		pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_dowm_sampled(new pcl::PointCloud<pcl::PointXYZ>);
+		std::vector<int> non_leaf_indices;
+		leaf_filter(cloud_dowm_sampled_with_leaf, non_leaf_indices);
+		pcl::copyPointCloud(*cloud_dowm_sampled_with_leaf, non_leaf_indices, *cloud_dowm_sampled);
+		if (m_pLogger) {
+			stringstream buff;
+			buff << m_pcdId << ": after leaf_filter dowm_sampled point cloud "
+				<< cloud_dowm_sampled->width * cloud_dowm_sampled->height << " data points (if < 50, return)";
+			m_pLogger->INFO(buff.str());
+		}
+		if (cloud_dowm_sampled->width * cloud_dowm_sampled->height < 50) {
+			return 1;
+		}
+		////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+		//5 seedling position,找到第一个位置上的植株
 		std::vector<int> first_seedling_cloud_idx;	//存储找到的第一个位置上植株茎上直线点的index
 		pcl::PointXYZ xz_center;					//存储找到的第一个位置上植株根部坐标
 		pcl::ModelCoefficients::Ptr line_model;		//存储找到的第一个位置上植株茎直线模型
@@ -240,7 +261,7 @@ namespace graft_cv {
 		}
 
 		////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-		//5 nearest seedling grab point selection,找到最接近指定高度的最优抓取点坐标
+		//6 nearest seedling grab point selection,找到最接近指定高度的最优抓取点坐标
 		pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_seedling_seed(new pcl::PointCloud<pcl::PointXYZ>);
 		pcl::copyPointCloud(*cloud_dowm_sampled, first_seedling_cloud_idx, *cloud_seedling_seed);
 		//改进思路:将茎直线上cloud_seedling_seed的点,提取周围邻域xz的宽度,在相同邻域cloud_dowm_sampled点云内提取xz的宽度
@@ -278,7 +299,7 @@ namespace graft_cv {
 			posinfo.rs_grab_z = selected_pt.z;
 		}
 		////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
-		//6 保存处理结果到图片
+		//7 保存处理结果到图片
 		cv::Mat rst_img = cv::Mat::zeros(cv::Size(1280,640),CV_8UC1);
 		gen_result_img(cloud_dowm_sampled, selected_pt, rst_img);
 		if (m_ppImgSaver && *m_ppImgSaver) {
@@ -520,6 +541,81 @@ namespace graft_cv {
 
 	//}
 	////////////////////////////////////////////////////////////
+	//叶子剔除
+void CRootStockGrabPoint::leaf_filter(
+	pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,	//输入,降采样的点云
+	std::vector<int> &stem_cloud_idx				//输出,除了叶子的点云序号
+) 
+{
+	//采用欧式距离聚类,对每一类的点云进行分析,剔除叶子
+	stem_cloud_idx.clear();
+
+	std::vector<pcl::PointIndices> cluster_indices;
+	pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
+	tree->setInputCloud(in_cloud);
+	
+
+	pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
+	ec.setClusterTolerance(2.5);
+	ec.setMinClusterSize(30);
+	ec.setMaxClusterSize(20000);
+	ec.setSearchMethod(tree);
+	ec.setInputCloud(in_cloud);
+	ec.extract(cluster_indices);
+	
+	for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin();
+		it != cluster_indices.end(); ++it) {
+		pcl::PointCloud<pcl::PointXYZ>::Ptr cluster_cloud(new pcl::PointCloud<pcl::PointXYZ>);
+		pcl::copyPointCloud(*in_cloud, *it, *cluster_cloud);		
+
+		//计算点云的pca
+		Eigen::Vector4f pcaCenteroid;
+		pcl::compute3DCentroid(*cluster_cloud, pcaCenteroid);
+		Eigen::Matrix3f covariance;
+		pcl::computeCovarianceMatrix(*cluster_cloud, pcaCenteroid, covariance);
+		Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance, Eigen::ComputeEigenvectors);
+		Eigen::Vector3f eigenValuesPCA = eigen_solver.eigenvalues();		
+		float e1, e2, e3;
+		e1 = std::sqrt(eigenValuesPCA(2));
+		e2 = std::sqrt(eigenValuesPCA(1));
+		e3 = std::sqrt(eigenValuesPCA(0));
+
+		float a1d = (e1 - e2) / e1;
+		float a2d = (e2 - e3) / e1;
+		float a3d = e3 / e1;
+
+		if (m_pLogger) {
+			stringstream buff;
+			buff << m_pcdId << ": ads=(" << a1d << "," << a2d << "," << a3d << "), pca_eigem_values=(" << e1
+				<< "," << e2 << "," << e3 << "), cluster_size=" << it->indices.size();
+			m_pLogger->INFO(buff.str());		
+		}	
+		if (m_cparam.image_show) {
+			if (a1d < 0.75) {
+				viewer_cloud(cluster_cloud, string("cluster_leaf"));
+			}
+			else {
+				viewer_cloud(cluster_cloud, string("cluster_stem"));
+			}
+		}
+		/*
+		特征值归一化处理:   a1d = (e1 - e2) / e1 
+		                    a2d = (e2 - e3) / e1 
+							a3d = e3 / e1 
+							
+							ei = sqrt(lamda_i)
+							
+							当点云线状分布时,a1d = 1, a2d = 0, a3d = 0
+							当点云面状分布时,a1d = 0, a2d = 1, a3d = 0
+							当点云球状分布时,a1d = 0, a2d = 0, a3d = 1
+		*/
+
+		if (a1d < 0.75) { continue; }
+		for (int idx : it->indices) {
+			stem_cloud_idx.push_back(idx);
+		}
+	}
+}
 void CRootStockGrabPoint::gen_all_seedling_positions(
 	pcl::PointXYZ&key_center,	//输入,已知的苗的坐标
 	std::vector<pcl::PointXYZ>&candidate_center	//输出,有倾斜苗的坐标
@@ -773,7 +869,28 @@ void CRootStockGrabPoint::line_filter(
 			ymin = m_cparam.sc_grab_ymin;
 			ymax = m_cparam.sc_grab_ymax;			
 		}
-		gen_all_seedling_positions(in_cloud->points.at(max_density_idx), clt_root);		
+		gen_all_seedling_positions(in_cloud->points.at(max_density_idx), clt_root);	
+		// 显示生成的每一个候选框				
+		/*if (m_cparam.image_show) {
+			std::vector<std::vector<int> > clt_line_idx;
+			std::vector<pcl::PointXYZ> clt_root_v;
+			std::vector<pcl::PointXYZ> clt_box_v;
+			for (auto&p : clt_root) {				
+				pcl::PointXYZ p_show(p.x, ymin, p.z);
+				clt_root_v.push_back(p_show);
+				pcl::PointXYZ min_point_aabb_ex;
+				pcl::PointXYZ max_point_aabb_ex;
+				min_point_aabb_ex.x = p.x - hole_step_radius;
+				min_point_aabb_ex.y = ymin;
+				min_point_aabb_ex.z = p.z - hole_step_radius;
+				max_point_aabb_ex.x = p.x + hole_step_radius;
+				max_point_aabb_ex.y = ymax;
+				max_point_aabb_ex.z = p.z + hole_step_radius;
+				clt_box_v.push_back(min_point_aabb_ex);
+				clt_box_v.push_back(max_point_aabb_ex);
+			}
+			viewer_cloud_cluster_box(in_cloud, clt_root_v, clt_box_v, clt_line_idx, std::string("candidate_box"));
+		}*/
 
 		// 每个位置点云情况,过滤		
 		std::vector<int> valid_index;		//初步有效的矩形index

+ 7 - 0
grab_point_rs.h

@@ -51,6 +51,13 @@ namespace graft_cv {
 			pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud
 		);*/
 		//<---------
+
+		//叶子剔除
+		void leaf_filter(
+			pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, 
+			std::vector<int> &stem_cloud_idx
+			);
+
 		void gen_all_seedling_positions(
 			pcl::PointXYZ&key_center,	//输入,已知的苗的坐标
 			std::vector<pcl::PointXYZ>&candidate_center	//输出,有倾斜苗的坐标

+ 1 - 1
graft_cv_api.cpp

@@ -19,7 +19,7 @@ extern CRITICAL_SECTION g_cs;
 namespace graft_cv
 {
 
-	char *g_version_str = "0.7.3";
+	char *g_version_str = "0.7.4";
 
 	//configure
 	string g_conf_file = "./gcv_conf.yml";