Commit 03dba8af authored by liuji's avatar liuji

detect range change

parent 72c0f559
......@@ -270,9 +270,9 @@ public:
for(int i = 0; i < objects->points.size(); i++)
{
if (objects->points[i].x < 1000)
if (objects->points[i].x < 50 && objects->points[i].y > -15 && objects->points[i].y < 15 ) //前向50m内 左右15m
{
if (objects->points[i].z > -1.3) //-1.5m以上的点做聚类处理
if (objects->points[i].z > -1.3 && objects->points[i].z < 3.5 ) //-1.3m-3.5m的点做聚类处理
close->points.push_back(objects->points[i]);
}
else
......@@ -325,7 +325,7 @@ public:
printf("=>close_objects_filtered voxel(dbscan before) after points size : %d \n", numPoints);
PointType* points = close_objects_filtered->points.data();
DBSCAN::Param param{.pointDimension = 3, .eps = 0.3, .minPoints = 20};
DBSCAN::Param param{.pointDimension = 3, .eps = 0.5, .minPoints = 20};//0.2 30 没box算是个临界点
DBSCAN dbscanHandler(param);
std::vector<std::vector<int>> clusterIndices;
......@@ -404,7 +404,7 @@ public:
tmp.x = it->x;
tmp.y = it->y;
tmp.z = it->z;
if (tmp.z < -1.3 || tmp.z > 1.2) //确定bbox内点云的范围
if (tmp.z < -1.3 || tmp.z > 3) //确定bbox内点云的范围
continue;
cloud_clustered->points.push_back(tmp);
tmp_filter_z->points.push_back(tmp);
......
......@@ -404,7 +404,7 @@ int LivoxFreeSpace::GroundSegment(int* pLabel,float *fPoints,int pointNum,float
pcl::computeMeanAndCovarianceMatrix(*cloud, cov, pc_mean);
Eigen::JacobiSVD<Eigen::MatrixXf> svd(cov,Eigen::DecompositionOptions::ComputeFullU);
normal_ = (svd.matrixU().col(2)); //第三个奇异向量(法向量)作为normal_
normal_ = (svd.matrixU().col(2)); //第三个奇异向量(更换坐标系的z轴即xy平面的法向量)作为normal_
Eigen::Vector3f seeds_mean = pc_mean.head<3>();
// normal.T * [x,y,z] = -d
//(0,0) 是 Eigen 矩阵表达式的索引,表示取其第 0 行第 0 列上的元素
......
// #include "sensor_msgs/PointCloud2.h"
// #include "geometry_msgs/Point.h"
// #include "geometry_msgs/Point32.h"
// #include "geometry_msgs/Polygon.h"
// #include "geometry_msgs/PolygonStamped.h"
// #include "nav_msgs/GridCells.h"
#include "pcl/conversions.h"
//#include "pcl_conversions/pcl_conversions.h"
#include "pcl/point_cloud.h"
#include "pcl/point_types.h"
#include <pcl/filters/voxel_grid.h>
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment