|
@@ -14,10 +14,11 @@
|
|
|
#include <pcl\visualization\cloud_viewer.h>
|
|
|
#include <pcl\filters\crop_box.h>
|
|
|
#include <pcl\filters\radius_outlier_removal.h>
|
|
|
+#include <pcl\filters\statistical_outlier_removal.h>
|
|
|
#include <pcl\filters\voxel_grid.h>
|
|
|
#include <pcl\common\common.h>
|
|
|
-//#include <pcl\features\moment_of_inertia_estimation.h>
|
|
|
-//#include <pcl\segmentation\sac_segmentation.h>
|
|
|
+#include <pcl\features\moment_of_inertia_estimation.h>
|
|
|
+#include <pcl\segmentation\sac_segmentation.h>
|
|
|
#include <math.h>
|
|
|
|
|
|
#include "grab_point_rs.h"
|
|
@@ -159,13 +160,14 @@ namespace graft_cv {
|
|
|
if(dtype == 0){
|
|
|
stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
|
|
|
}
|
|
|
+ double remove_radius = stem_radius * 2.0;
|
|
|
+
|
|
|
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ror(new pcl::PointCloud<pcl::PointXYZ>);
|
|
|
- pcl::RadiusOutlierRemoval<pcl::PointXYZ> ror;
|
|
|
+ pcl::RadiusOutlierRemoval<pcl::PointXYZ> ror(false);
|
|
|
ror.setInputCloud(cloud_inbox);
|
|
|
- ror.setRadiusSearch(stem_radius);
|
|
|
+ ror.setRadiusSearch(remove_radius);
|
|
|
ror.setMinNeighborsInRadius(nb_points);
|
|
|
ror.filter(*cloud_ror);
|
|
|
-
|
|
|
if (m_pLogger) {
|
|
|
stringstream buff;
|
|
|
buff << "RadiusOutlierRemoval filtered point cloud " << cloud_ror->width * cloud_ror->height << " data points. param stem_radius="<<
|
|
@@ -176,13 +178,13 @@ namespace graft_cv {
|
|
|
return 1;
|
|
|
}
|
|
|
|
|
|
- if (m_cparam.image_show) {
|
|
|
+ /*if (m_cparam.image_show) {
|
|
|
viewer_cloud(cloud_ror, std::string("cloud_ror"));
|
|
|
- }
|
|
|
+ }*/
|
|
|
if (m_pLogger) {
|
|
|
m_pLogger->INFO("end ror");
|
|
|
}
|
|
|
-
|
|
|
+ ///////////////////////////////////////////////////////////////////////////////
|
|
|
//3 voxel grid down sampling
|
|
|
if (m_pLogger) {
|
|
|
m_pLogger->INFO("begin down");
|
|
@@ -195,19 +197,21 @@ namespace graft_cv {
|
|
|
|
|
|
if (m_pLogger) {
|
|
|
stringstream buff;
|
|
|
- buff << "VoxelGrid dowm_sampled point cloud " << cloud_dowm_sampled->width * cloud_dowm_sampled->height << " data points (if < 200, return)";
|
|
|
+ buff << "VoxelGrid 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;
|
|
|
}
|
|
|
|
|
|
- if (m_cparam.image_show) {
|
|
|
+ /*if (m_cparam.image_show) {
|
|
|
viewer_cloud(cloud_dowm_sampled, std::string("cloud_dowm_sampled"));
|
|
|
- }
|
|
|
+ }*/
|
|
|
if (m_pLogger) {
|
|
|
m_pLogger->INFO("end down");
|
|
|
}
|
|
|
+
|
|
|
+ ///////////////////////////////////////////////////////////////////////////////
|
|
|
//4 seedling position
|
|
|
std::vector<int> first_seedling_cloud_idx;
|
|
|
pcl::PointXYZ xz_center;
|
|
@@ -218,12 +222,14 @@ namespace graft_cv {
|
|
|
find_seedling_position(cloud_dowm_sampled, first_seedling_cloud_idx, xz_center);
|
|
|
if (m_pLogger) {
|
|
|
stringstream buff;
|
|
|
- buff << "after find_seedling_position(), foud first seedling seeds points size " << first_seedling_cloud_idx .size();
|
|
|
+ buff << "after find_seedling_position(), foud first seedling seeds points size " << first_seedling_cloud_idx.size();
|
|
|
m_pLogger->INFO(buff.str());
|
|
|
}
|
|
|
if (m_pLogger) {
|
|
|
m_pLogger->INFO("end find seedling position");
|
|
|
}
|
|
|
+
|
|
|
+ ///////////////////////////////////////////////////////////////////////////////
|
|
|
//5 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);
|
|
@@ -303,7 +309,7 @@ namespace graft_cv {
|
|
|
|
|
|
|
|
|
//viewer_cloud(cloud_cand_demo, std::string("cloud_cand_demo"));
|
|
|
- viewer_cloud_debug(cloud_cand_demo, selected_pt, std::string("cloud_cand_demo"));
|
|
|
+ viewer_cloud_debug(cloud_cand_demo, selected_pt, xz_center, std::string("cloud_cand_demo"));
|
|
|
}
|
|
|
return 0;
|
|
|
}
|
|
@@ -456,21 +462,25 @@ namespace graft_cv {
|
|
|
|
|
|
//}
|
|
|
////////////////////////////////////////////////////////////
|
|
|
- void CRootStockGrabPoint::find_seedling_position(
|
|
|
+ void CRootStockGrabPoint::find_seedling_position(
|
|
|
pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
|
|
|
std::vector<int> &first_seedling_cloud_idx,
|
|
|
pcl::PointXYZ&xz_center
|
|
|
)
|
|
|
{
|
|
|
+
|
|
|
+ float hole_step = 40.0; //穴盘中穴间距
|
|
|
+ float hole_step_radius = hole_step / 2.0;
|
|
|
+
|
|
|
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d(new pcl::PointCloud < pcl::PointXYZ>);
|
|
|
pcl::copyPointCloud(*in_cloud, *cloud2d);
|
|
|
for (auto&pt : *cloud2d) {
|
|
|
pt.y = 0.0;
|
|
|
}
|
|
|
|
|
|
- if(m_cparam.image_show){
|
|
|
+ /*if(m_cparam.image_show){
|
|
|
viewer_cloud(cloud2d, std::string("cloud2d"));
|
|
|
- }
|
|
|
+ } */
|
|
|
|
|
|
double radius = m_cparam.rs_grab_stem_diameter;
|
|
|
if (m_dtype == 0) {
|
|
@@ -485,7 +495,7 @@ namespace graft_cv {
|
|
|
int k = kdtree.radiusSearch(cloud2d->points.at(i), radius, idx, dist_sqr);
|
|
|
counter.push_back(k);
|
|
|
}
|
|
|
- int th = (int)(otsu(counter));
|
|
|
+ int th = (int)(otsu(counter));
|
|
|
std::vector<int> index;
|
|
|
for (size_t i = 0; i < counter.size(); ++i) {
|
|
|
if (counter.at(i) >= th) {
|
|
@@ -523,9 +533,81 @@ namespace graft_cv {
|
|
|
m_pLogger->INFO(buff.str());
|
|
|
}
|
|
|
|
|
|
+ if (m_cparam.image_show) {
|
|
|
+ pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
|
|
|
+ pcl::copyPointCloud(*cloud2d_pos, *cloud_cluster);
|
|
|
+
|
|
|
+ for (auto& pt : *cloud_cluster) {
|
|
|
+ pt.r = 255;
|
|
|
+ pt.g = 255;
|
|
|
+ pt.b = 255;
|
|
|
+ }
|
|
|
+ viewer_cloud_cluster(cloud_cluster, cluster_center, std::string("cloud2d_cluster_pos"));
|
|
|
+ }
|
|
|
+ //对每个类别进行检测,剔除不是茎的类别
|
|
|
+ std::vector<pcl::PointXYZ> clt_root;
|
|
|
+ std::vector<pcl::PointXYZ> clt_box;
|
|
|
+ std::vector<std::vector<int> > clt_line_idx;
|
|
|
+
|
|
|
+ for (size_t i = 0; i < cluster_center.size(); ++i) {
|
|
|
+ pcl::PointIndices cluster_idxs;
|
|
|
+ for (auto idx_clt : cluster_member.at(i)) {
|
|
|
+ int idx_raw = index.at(idx_clt);
|
|
|
+ cluster_idxs.indices.push_back(idx_raw);
|
|
|
+ }
|
|
|
+ pcl::PointCloud<pcl::PointXYZ>::Ptr clt_cloud(new pcl::PointCloud < pcl::PointXYZ>);
|
|
|
+ pcl::copyPointCloud(*in_cloud, cluster_idxs, *clt_cloud);
|
|
|
+ //计算每一个茎的外接矩形
|
|
|
+ pcl::PointXYZ min_point_aabb;
|
|
|
+ pcl::PointXYZ max_point_aabb;
|
|
|
+ pcl::MomentOfInertiaEstimation<pcl::PointXYZ> feature_extractor;
|
|
|
+ feature_extractor.setInputCloud(clt_cloud);
|
|
|
+ feature_extractor.compute();
|
|
|
+ feature_extractor.getAABB(min_point_aabb, max_point_aabb);
|
|
|
+ //扩展矩形范围
|
|
|
+ pcl::PointXYZ min_point_aabb_ex;
|
|
|
+ pcl::PointXYZ max_point_aabb_ex;
|
|
|
+ min_point_aabb_ex.x = 0.5*(min_point_aabb.x + max_point_aabb.x) - hole_step_radius;
|
|
|
+ min_point_aabb_ex.y = m_cparam.sc_grab_ymin;
|
|
|
+ if (m_dtype != 0) { min_point_aabb_ex.y = m_cparam.rs_grab_ymin; }
|
|
|
+ min_point_aabb_ex.z = 0.5*(min_point_aabb.z + max_point_aabb.z) - hole_step_radius;
|
|
|
+
|
|
|
+ max_point_aabb_ex.x = 0.5*(min_point_aabb.x + max_point_aabb.x) + hole_step_radius;
|
|
|
+ max_point_aabb_ex.y = m_cparam.sc_grab_ymax;
|
|
|
+ if (m_dtype != 0) { max_point_aabb_ex.y = m_cparam.rs_grab_ymax; }
|
|
|
+ max_point_aabb_ex.z = 0.5*(min_point_aabb.z + max_point_aabb.z) + hole_step_radius;
|
|
|
+
|
|
|
+ /////////////////////////////////
|
|
|
+ //扩展矩形内直线检测
|
|
|
+ std::vector<int>line_idx;
|
|
|
+ find_line_in_cube(in_cloud, min_point_aabb_ex, max_point_aabb_ex, line_idx);
|
|
|
+ clt_line_idx.push_back(line_idx);
|
|
|
+ //找到line_idx中y最小的那个点的idx
|
|
|
+ int line_root_idx = -1;
|
|
|
+ float line_root_y_min = 10000.0;
|
|
|
+ for (size_t lidx = 0; lidx < line_idx.size();++lidx) {
|
|
|
+ int raw_idx = line_idx.at(lidx);
|
|
|
+ if (in_cloud->at(raw_idx).y < line_root_y_min) {
|
|
|
+ line_root_y_min = in_cloud->at(raw_idx).y;
|
|
|
+ line_root_idx = raw_idx;
|
|
|
+ }
|
|
|
+ }
|
|
|
+ //找到底部中心点,然后找到根部坐标
|
|
|
+ pcl::PointXYZ pt_root;
|
|
|
+ pt_root = in_cloud->at(line_root_idx);
|
|
|
+
|
|
|
+ clt_root.push_back(pt_root);
|
|
|
+ clt_box.push_back(min_point_aabb_ex);
|
|
|
+ clt_box.push_back(max_point_aabb_ex);
|
|
|
+ //viewer_cloud(clt_cloud, std::string("cluster"));
|
|
|
+ }
|
|
|
+ if (m_cparam.image_show) {
|
|
|
+ viewer_cloud_cluster_box(in_cloud, clt_root, clt_box, clt_line_idx, std::string("cloud2d_cluster_box"));
|
|
|
+ }
|
|
|
+
|
|
|
//sort cluster center, get the frontest leftest one
|
|
|
std::vector<float> cluster_index;
|
|
|
- for (auto&pt : cluster_center) {
|
|
|
+ for (auto&pt : clt_root) {
|
|
|
float idx = pt.x - pt.z;
|
|
|
cluster_index.push_back(idx);
|
|
|
}
|
|
@@ -535,13 +617,12 @@ namespace graft_cv {
|
|
|
}
|
|
|
|
|
|
first_seedling_cloud_idx.clear();
|
|
|
- for (auto&v : cluster_member.at(first_idx)) {
|
|
|
- size_t i = index.at(v);
|
|
|
- first_seedling_cloud_idx.push_back(i);
|
|
|
+ for (auto&v : clt_line_idx.at(first_idx)) {
|
|
|
+ first_seedling_cloud_idx.push_back(v);
|
|
|
}
|
|
|
- xz_center.x = cluster_center.at(first_idx).x;
|
|
|
- xz_center.y = cluster_center.at(first_idx).y;
|
|
|
- xz_center.z = cluster_center.at(first_idx).z;
|
|
|
+ xz_center.x = clt_root.at(first_idx).x;
|
|
|
+ xz_center.y = clt_root.at(first_idx).y;
|
|
|
+ xz_center.z = clt_root.at(first_idx).z;
|
|
|
|
|
|
if (m_pLogger) {
|
|
|
stringstream buff;
|
|
@@ -550,6 +631,65 @@ namespace graft_cv {
|
|
|
m_pLogger->INFO(buff.str());
|
|
|
}
|
|
|
}
|
|
|
+ void CRootStockGrabPoint::find_line_in_cube(
|
|
|
+ pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //输入,整体点云
|
|
|
+ pcl::PointXYZ& min_pt_ex, //输入,
|
|
|
+ pcl::PointXYZ& max_pt_ex, //输入,
|
|
|
+ std::vector<int>& out_idx //输出,直线上点的index, 基于输入整体点云
|
|
|
+ )
|
|
|
+ {
|
|
|
+ out_idx.clear();
|
|
|
+ pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
|
|
|
+ pcl::CropBox<pcl::PointXYZ> box_filter;
|
|
|
+ std::vector<int>inbox_idx;
|
|
|
+ box_filter.setMin(Eigen::Vector4f(min_pt_ex.x, min_pt_ex.y, min_pt_ex.z, 1));
|
|
|
+ box_filter.setMax(Eigen::Vector4f(max_pt_ex.x, max_pt_ex.y, max_pt_ex.z, 1));
|
|
|
+
|
|
|
+ box_filter.setNegative(false);
|
|
|
+ box_filter.setInputCloud(in_cloud);
|
|
|
+ box_filter.filter(inbox_idx);
|
|
|
+ pcl::copyPointCloud(*in_cloud, inbox_idx, *cloud_inbox);
|
|
|
+
|
|
|
+
|
|
|
+ //找到inbox点云中的直线
|
|
|
+ float stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
|
|
|
+ if (m_dtype == 0) {
|
|
|
+ stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
|
|
|
+ }
|
|
|
+ pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
|
|
|
+ pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
|
|
|
+ pcl::SACSegmentation<pcl::PointXYZ> seg;
|
|
|
+ seg.setOptimizeCoefficients(true);
|
|
|
+ seg.setModelType(pcl::SACMODEL_LINE);
|
|
|
+ seg.setDistanceThreshold(stem_radius);
|
|
|
+ seg.setInputCloud(cloud_inbox);
|
|
|
+ seg.segment(*inliers, *coefficients);
|
|
|
+
|
|
|
+ int idx_raw = 0;
|
|
|
+ for (auto& idx : inliers->indices) {
|
|
|
+ idx_raw = inbox_idx.at(idx);
|
|
|
+ out_idx.push_back(idx_raw);
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+ if (m_cparam.image_show) {
|
|
|
+ pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_line(new pcl::PointCloud<pcl::PointXYZ>);
|
|
|
+ pcl::copyPointCloud(*cloud_inbox, *inliers, *cloud_line);
|
|
|
+
|
|
|
+ pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("line in cluster"));
|
|
|
+ viewer->addPointCloud<pcl::PointXYZ>(cloud_inbox, "cluster");
|
|
|
+ viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "cluster");
|
|
|
+ viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "cluster");
|
|
|
+
|
|
|
+ viewer->addPointCloud(cloud_line, "fit_line");
|
|
|
+ viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "fit_line");
|
|
|
+ viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "fit_line");
|
|
|
+ while (!viewer->wasStopped()) {
|
|
|
+ viewer->spinOnce(100);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ }
|
|
|
+
|
|
|
void CRootStockGrabPoint::crop_nn_analysis(
|
|
|
pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
|
|
|
pcl::PointCloud<pcl::PointXYZ>::Ptr seed_cloud,
|
|
@@ -915,21 +1055,25 @@ namespace graft_cv {
|
|
|
boost::this_thread::sleep(boost::posix_time::microseconds(100000));
|
|
|
}
|
|
|
}
|
|
|
- void CRootStockGrabPoint::viewer_cloud_debug(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, pcl::PointXYZ &p, std::string&winname)
|
|
|
+ void CRootStockGrabPoint::viewer_cloud_debug(
|
|
|
+ pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
|
|
|
+ pcl::PointXYZ &p,
|
|
|
+ pcl::PointXYZ &root_pt,
|
|
|
+ std::string&winname)
|
|
|
{
|
|
|
pcl::visualization::PCLVisualizer viewer(winname);
|
|
|
//viewer.runOnVisualizationThreadOnce(viewerOneOff);
|
|
|
viewer.addPointCloud(cloud);
|
|
|
viewer.addCoordinateSystem();
|
|
|
- pcl::PointXYZ p0, x1, y1,p00,x0,y0;
|
|
|
+ pcl::PointXYZ p0, x1, y1,p00,x0,y0, root_px0, root_px1, root_py0,root_py1;
|
|
|
p0.x = p.x;
|
|
|
p0.y = p.y;
|
|
|
p0.z = p.z;
|
|
|
- x1.x = p.x + 400.0;
|
|
|
+ x1.x = p.x + 100.0;
|
|
|
x1.y = p.y;
|
|
|
x1.z = p.z;
|
|
|
y1.x = p.x;
|
|
|
- y1.y = p.y + 200.0;
|
|
|
+ y1.y = p.y + 20.0;
|
|
|
y1.z = p.z;
|
|
|
|
|
|
p00.x = 0.0;
|
|
@@ -941,6 +1085,21 @@ namespace graft_cv {
|
|
|
y0.x = 0.0;
|
|
|
y0.y = 300.0;
|
|
|
y0.z = p.z;
|
|
|
+
|
|
|
+ root_px0.x = root_pt.x - 5.0;
|
|
|
+ root_px0.y = root_pt.y;
|
|
|
+ root_px0.z = root_pt.z;
|
|
|
+ root_px1.x = root_pt.x + 5.0;
|
|
|
+ root_px1.y = root_pt.y;
|
|
|
+ root_px1.z = root_pt.z;
|
|
|
+
|
|
|
+ root_py0.x = root_pt.x;
|
|
|
+ root_py0.y = root_pt.y - 5.0;
|
|
|
+ root_py0.z = root_pt.z;
|
|
|
+ root_py1.x = root_pt.x;
|
|
|
+ root_py1.y = root_pt.y + 5.0;
|
|
|
+ root_py1.z = root_pt.z;
|
|
|
+
|
|
|
|
|
|
viewer.addLine(p0, x1, 255, 0, 0, "x");
|
|
|
viewer.addLine(p0, y1, 0, 255, 0, "y");
|
|
@@ -948,10 +1107,108 @@ namespace graft_cv {
|
|
|
viewer.addLine(p00, x0, 255, 0, 0, "x0");
|
|
|
viewer.addLine(p00, y0, 0, 255, 0, "y0");
|
|
|
|
|
|
+ viewer.addLine(root_px0, root_px1, 255, 0, 0, "rootx");
|
|
|
+ viewer.addLine(root_py0, root_py1, 0, 255, 0, "rooty");
|
|
|
+
|
|
|
while (!viewer.wasStopped()) {
|
|
|
viewer.spinOnce(100);
|
|
|
boost::this_thread::sleep(boost::posix_time::microseconds(100000));
|
|
|
}
|
|
|
}
|
|
|
|
|
|
+ void CRootStockGrabPoint::viewer_cloud_cluster(
|
|
|
+ pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
|
|
|
+ std::vector<pcl::PointXYZ>cluster_center,
|
|
|
+ std::string&winname)
|
|
|
+ {
|
|
|
+ pcl::visualization::PCLVisualizer viewer(winname);
|
|
|
+ viewer.addPointCloud(cloud);
|
|
|
+ viewer.addCoordinateSystem();
|
|
|
+ int cnt = 0;
|
|
|
+ char buf[8];
|
|
|
+ for (auto& p : cluster_center) {
|
|
|
+ pcl::PointXYZ px0, px1, py1, py0;
|
|
|
+ px0.x = p.x-5.0;
|
|
|
+ px0.y = p.y;
|
|
|
+ px0.z = p.z;
|
|
|
+ px1.x = p.x + 5.0;
|
|
|
+ px1.y = p.y;
|
|
|
+ px1.z = p.z;
|
|
|
+
|
|
|
+ py0.x = p.x;
|
|
|
+ py0.y = p.y - 5.0;
|
|
|
+ py0.z = p.z;
|
|
|
+ py1.x = p.x;
|
|
|
+ py1.y = p.y + 5.0;
|
|
|
+ py1.z = p.z;
|
|
|
+
|
|
|
+ viewer.addLine(px0, px1, 255, 0, 0, "x" + string(_itoa(cnt, buf,10)));
|
|
|
+ viewer.addLine(py0, py1, 0, 255, 0, "y" + string(_itoa(cnt, buf, 10)));
|
|
|
+ cnt += 1;
|
|
|
+ }
|
|
|
+
|
|
|
+
|
|
|
+ while (!viewer.wasStopped()) {
|
|
|
+ viewer.spinOnce(100);
|
|
|
+ boost::this_thread::sleep(boost::posix_time::microseconds(100000));
|
|
|
+ }
|
|
|
+
|
|
|
+ }
|
|
|
+ void CRootStockGrabPoint::viewer_cloud_cluster_box(
|
|
|
+ pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
|
|
|
+ std::vector<pcl::PointXYZ>&cluster_center,
|
|
|
+ std::vector<pcl::PointXYZ>&cluster_box,
|
|
|
+ std::vector<std::vector<int> >& clt_line_idx,
|
|
|
+ std::string&winname)
|
|
|
+ {
|
|
|
+ pcl::visualization::PCLVisualizer viewer(winname);
|
|
|
+ viewer.addCoordinateSystem();
|
|
|
+ viewer.addPointCloud<pcl::PointXYZ>(cloud, "all_cloud");
|
|
|
+ viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "all_cloud");
|
|
|
+ viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "all_cloud");
|
|
|
+
|
|
|
+ int cnt = 0;
|
|
|
+ char buf[8];
|
|
|
+ for (size_t i = 0; i < cluster_center.size();++i) {
|
|
|
+ pcl::PointXYZ &p = cluster_center.at(i);
|
|
|
+ pcl::PointXYZ px0, px1, py1, py0;
|
|
|
+ px0.x = p.x - 5.0;
|
|
|
+ px0.y = p.y;
|
|
|
+ px0.z = p.z;
|
|
|
+ px1.x = p.x + 5.0;
|
|
|
+ px1.y = p.y;
|
|
|
+ px1.z = p.z;
|
|
|
+
|
|
|
+ py0.x = p.x;
|
|
|
+ py0.y = p.y - 5.0;
|
|
|
+ py0.z = p.z;
|
|
|
+ py1.x = p.x;
|
|
|
+ py1.y = p.y + 5.0;
|
|
|
+ py1.z = p.z;
|
|
|
+
|
|
|
+ viewer.addLine(px0, px1, 255, 0, 0, "x" + string(_itoa(cnt, buf, 10)));
|
|
|
+ viewer.addLine(py0, py1, 0, 255, 0, "y" + string(_itoa(cnt, buf, 10)));
|
|
|
+
|
|
|
+ //box
|
|
|
+ pcl::PointXYZ & min_pt = cluster_box.at(2 * i);
|
|
|
+ pcl::PointXYZ & max_pt = cluster_box.at(2 * i + 1);
|
|
|
+ viewer.addCube(min_pt.x, max_pt.x, min_pt.y, max_pt.y, min_pt.z, max_pt.z, 0.5,0.5,0.0,"AABB_"+string(_itoa(cnt, buf, 10)));
|
|
|
+ viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_REPRESENTATION,
|
|
|
+ pcl::visualization::PCL_VISUALIZER_REPRESENTATION_WIREFRAME, "AABB_" + string(_itoa(cnt, buf, 10)));
|
|
|
+
|
|
|
+ pcl::PointCloud<pcl::PointXYZ>::Ptr line_cloud(new pcl::PointCloud<pcl::PointXYZ>);
|
|
|
+ pcl::copyPointCloud(*cloud, clt_line_idx.at(i), *line_cloud);
|
|
|
+ viewer.addPointCloud(line_cloud, "fit_line" + string(_itoa(cnt, buf, 10)));
|
|
|
+ viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "fit_line" + string(_itoa(cnt, buf, 10)));
|
|
|
+ viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "fit_line" + string(_itoa(cnt, buf, 10)));
|
|
|
+
|
|
|
+ cnt += 1;
|
|
|
+ }
|
|
|
+ while (!viewer.wasStopped()) {
|
|
|
+ viewer.spinOnce(100);
|
|
|
+ boost::this_thread::sleep(boost::posix_time::microseconds(100000));
|
|
|
+ }
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
};
|