#include #include #include #include typedef pcl::PointXYZINormal PointType; using namespace std; ros::Publisher pub_full, pub_surf, pub_corn; enum LID_TYPE{MID, HORIZON, VELO16, OUST64}; enum Feature{Nor, Poss_Plane, Real_Plane, Edge_Jump, Edge_Plane, Wire, ZeroPoint}; enum Surround{Prev, Next}; enum E_jump{Nr_nor, Nr_zero, Nr_180, Nr_inf, Nr_blind}; struct orgtype { double range; // sqrt(x*x+y*y) double dista; // 该点与后一个点的距离平方 double angle[2]; // 前(后)一个点、该点、原点所成角度 double intersect; // 前后点与该点的夹角 E_jump edj[2]; // 每个点前后点的关系 // Surround nor_dir; Feature ftype; orgtype() { range = 0; edj[Prev] = Nr_nor; edj[Next] = Nr_nor; ftype = Nor; intersect = 2; } }; // const int hor_line = 6; const double rad2deg = 180*M_1_PI; int lidar_type; double blind, inf_bound; int N_SCANS; int group_size; double disA, disB; double limit_maxmid, limit_midmin, limit_maxmin; double p2l_ratio; double jump_up_limit, jump_down_limit; double cos160; double edgea, edgeb; double smallp_intersect, smallp_ratio; int point_filter_num; void mid_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); void horizon_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg); void velo16_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); void oust64_handler(const sensor_msgs::PointCloud2::ConstPtr &msg); void give_feature(pcl::PointCloud &pl, vector &types, pcl::PointCloud &pl_corn, pcl::PointCloud &pl_surf); void pub_func(pcl::PointCloud &pl, ros::Publisher pub, const ros::Time &ct); int plane_judge(const pcl::PointCloud &pl, vector &types, uint i, uint &i_nex, Eigen::Vector3d &curr_direct); bool small_plane(const pcl::PointCloud &pl, vector &types, uint i_cur, uint &i_nex, Eigen::Vector3d &curr_direct); bool edge_jump_judge(const pcl::PointCloud &pl, vector &types, uint i, Surround nor_dir); int main(int argc, char **argv) { ros::init(argc, argv, "feature_extract"); ros::NodeHandle n; // lidar_type = MID; // blind = 0.5; // inf_bound = 10; // // N_SCANS = 1; // group_size = 8; // disA = 0.01; disB = 0.1; // p2l_ratio = 400; // limit_maxmid = 9; // limit_midmin = 16; // // limit_maxmin; // jump_up_limit = cos(175.0/180*M_PI); // jump_down_limit = cos(5.0/180*M_PI); // cos160 = cos(160.0/180*M_PI); // edgea = 3; // 2 // edgeb = 0.05; // 0.1 // smallp_intersect = cos(170.0/180*M_PI); // smallp_ratio = 1.3; // point_filter_num = 4; n.param("lidar_type", lidar_type, 0); n.param("blind", blind, 0.5); n.param("inf_bound", inf_bound, 10); n.param("N_SCANS", N_SCANS, 1); n.param("group_size", group_size, 8); n.param("disA", disA, 0.01); n.param("disB", disB, 0.1); n.param("p2l_ratio", p2l_ratio, 400); n.param("limit_maxmid", limit_maxmid, 9); n.param("limit_midmin", limit_midmin, 16); n.param("limit_maxmin", limit_maxmin, 3.24); n.param("jump_up_limit", jump_up_limit, 175.0); n.param("jump_down_limit", jump_down_limit, 5.0); n.param("cos160", cos160, 160.0); n.param("edgea", edgea, 3); n.param("edgeb", edgeb, 0.05); n.param("smallp_intersect", smallp_intersect, 170.0); n.param("smallp_ratio", smallp_ratio, 1.2); n.param("point_filter_num", point_filter_num, 4); jump_up_limit = cos(jump_up_limit/180*M_PI); jump_down_limit = cos(jump_down_limit/180*M_PI); cos160 = cos(cos160/180*M_PI); smallp_intersect = cos(smallp_intersect/180*M_PI); // lidar_type = HORIZON; // blind = 0.5; // inf_bound = 10; // N_SCANS = 6; // group_size = 8; // disA = 0.01; disB = 0.1; // p2l_ratio = 225; // limit_maxmid = 6.25; // limit_midmin = 6.25; // // limit_maxmin; // jump_up_limit = cos(170.0/180*M_PI); // jump_down_limit = cos(8.0/180*M_PI); // cos160 = cos(160.0/180*M_PI); // edgea = 2; // edgeb = 0.1; // smallp_intersect = cos(170.0/180*M_PI); // smallp_ratio = 1.4; // lidar_type = VELO16; // blind = 0.5; // inf_bound = 10; // N_SCANS = 16; // group_size = 9; // disA = 0.015; disB = 0.3; // p2l_ratio = 400; // // limit_maxmid = 9; // // limit_midmin = 16; // limit_maxmin = 3.24; // jump_up_limit = cos(170.0/180*M_PI); // jump_down_limit = cos(8.0/180*M_PI); // cos160 = cos(160.0/180*M_PI); // edgea = 2; // 2 // edgeb = 0.1; // 0.1 // smallp_intersect = cos(170.0/180*M_PI); // smallp_ratio = 1.4; // lidar_type = OUST64; // lidar的种类 // blind = 0.5; // lidar的盲区(非平方) // inf_bound = 10; // 无穷远点最近点的距离限制(非平方) // N_SCANS = 64; // 6, 16, 64 // group_size = 9; // 7->8 9 // disA = 0.015; // 0.015 // Ax+B // disB = 0.3; // 0.3 // p2l_ratio = 196; // 225 196 // // limit_maxmid = 9; // 6.25 // // limit_midmin = 16; // 6.25 // limit_maxmin = 6.25; // 6.25 // jump_up_limit = cos(170.0/180*M_PI); // jump_down_limit = cos(8.0/180*M_PI); // cos160 = cos(160.0/180*M_PI); // edgea = 2.5; // 2 // edgeb = 0.2; // 0.1 // smallp_intersect = cos(170.0/180*M_PI); // smallp_ratio = 1.4; ros::Subscriber sub_points; switch(lidar_type) { case MID: printf("MID40-70\n"); sub_points = n.subscribe("/livox/lidar", 1000, mid_handler); // sub_points = n.subscribe("/livox/lidar_1LVDG1S006J5GZ3", 1000, mid_handler); break; case HORIZON: printf("HORIZON_MID70pro\n"); sub_points = n.subscribe("/livox/lidar", 1000, horizon_handler); break; case VELO16: printf("VELO16\n"); sub_points = n.subscribe("/velodyne_points", 1000, velo16_handler); break; case OUST64: printf("OUST64\n"); sub_points = n.subscribe("/os1_cloud_node/points", 1000, oust64_handler); break; default: printf("Lidar type is wrong.\n"); exit(0); break; } pub_full = n.advertise("/livox_cloud", 20); pub_surf = n.advertise("/laser_cloud_flat", 20); pub_corn = n.advertise("/laser_cloud_sharp", 20); ros::spin(); return 0; } double vx, vy, vz; void mid_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) { pcl::PointCloud pl; pcl::fromROSMsg(*msg, pl); pcl::PointCloud pl_corn, pl_surf; vector types; uint plsize = pl.size()-1; pl_corn.reserve(plsize); pl_surf.reserve(plsize); types.resize(plsize+1); for(uint i=0; i> a; // if(a == 0) // { // exit(0); // } } void horizon_handler(const livox_ros_driver::CustomMsg::ConstPtr &msg) { double t1 = omp_get_wtime(); vector> pl_buff(N_SCANS); vector> typess(N_SCANS); pcl::PointCloud pl_full, pl_corn, pl_surf; uint plsize = msg->point_num; pl_corn.reserve(plsize); pl_surf.reserve(plsize); pl_full.resize(plsize); for(int i=0; ipoints[i].line < N_SCANS) { pl_full[i].x = msg->points[i].x; pl_full[i].y = msg->points[i].y; pl_full[i].z = msg->points[i].z; pl_full[i].intensity = msg->points[i].reflectivity; pl_full[i].curvature = msg->points[i].offset_time / float(1000000); //use curvature as time of each laser points pl_buff[msg->points[i].line].push_back(pl_full[i]); } } for(int j=0; j &pl = pl_buff[j]; vector &types = typess[j]; plsize = pl.size(); types.resize(plsize); plsize--; for(uint i=0; itimebase); pub_func(pl_full, pub_full, ct); pub_func(pl_surf, pub_surf, ct); pub_func(pl_corn, pub_corn, ct); std::cout<<"[~~~~~~~~~~~~ Feature Extract ]: time: "<< omp_get_wtime() - t1<<" "<header.stamp.toSec()< pl_orig; pcl::fromROSMsg(*msg, pl_orig); pcl::PointCloud pl_corn, pl_surf, pl_full; vector> pl_buff(N_SCANS); vector> typess(N_SCANS); uint plsize = pl_orig.size(); pl_corn.reserve(plsize); pl_surf.reserve(plsize); pl_full.reserve(plsize); for(int i=0; i blind) { if(stat == 0) { stat = 1; idx++; } double ang = atan(ap.z / leng)*rad2deg; scanID = int((ang + 15) / 2 + 0.5); if(scanID>=N_SCANS || scanID <0) { continue; } pl_buff[scanID][idx] = ap; typess[scanID][idx].range = leng; pl_full.push_back(ap); } else { stat = 0; } } idx++; for(int j=0; j &pl = pl_buff[j]; vector &types = typess[j]; pl.erase(pl.begin()+idx, pl.end()); types.erase(types.begin()+idx, types.end()); plsize = idx - 1; for(uint i=0; i pl_orig; pcl::fromROSMsg(*msg, pl_orig); vector> pl_buff(N_SCANS); vector> typess(N_SCANS); pcl::PointCloud pl_corn, pl_surf; uint plsize = pl_orig.size(); pl_corn.reserve(plsize); pl_surf.reserve(plsize); for(int i=0; i &pl = pl_buff[j]; vector &types = typess[j]; plsize = pl.size() - 1; types.resize(plsize+1); for(uint i=0; i &pl, vector &types, pcl::PointCloud &pl_corn, pcl::PointCloud &pl_surf) { uint plsize = pl.size(); uint plsize2; if(plsize == 0) { printf("something wrong\n"); return; } uint head = 0; while(types[head].range < blind) { head++; } // 平面点检测 plsize2 = plsize - group_size; Eigen::Vector3d curr_direct(Eigen::Vector3d::Zero()); Eigen::Vector3d last_direct(Eigen::Vector3d::Zero()); uint i_nex, i2; uint last_i = 0; uint last_i_nex = 0; // 0:上次状态无用 1:上次为平面组 int last_state = 0; int plane_type; for(uint i=head; i0.5) if(last_state==1 && last_direct.norm()>0.1) { double mod = last_direct.transpose() * curr_direct; if(mod>-0.707 && mod<0.707) { types[i].ftype = Edge_Plane; } else { types[i].ftype = Real_Plane; } } i = i_nex - 1; last_state = 1; } else if(plane_type == 2) { i = i_nex; last_state = 0; } else if(plane_type == 0) { if(last_state == 1) { uint i_nex_tem; // 临时变量 uint j; for(j=last_i+1; j<=last_i_nex; j++) { uint i_nex_tem2 = i_nex_tem; Eigen::Vector3d curr_direct2; // curr_direct临时变量 uint ttem = plane_judge(pl, types, j, i_nex_tem, curr_direct2); if(ttem != 1) { i_nex_tem = i_nex_tem2; break; } curr_direct = curr_direct2; } if(j == last_i+1) { last_state = 0; } else { for(uint k=last_i_nex; k<=i_nex_tem; k++) { if(k != i_nex_tem) { types[k].ftype = Real_Plane; } else { types[k].ftype = Poss_Plane; } } i = i_nex_tem-1; i_nex = i_nex_tem; i2 = j-1; last_state = 1; } } } last_i = i2; last_i_nex = i_nex; last_direct = curr_direct; } plsize2 = plsize - 3; // for(uint i=head+3; i=Real_Plane) // { // continue; // } // if(types[i-1].dista<1e-16 || types[i].dista<1e-16) // { // continue; // } // Eigen::Vector3d vec_a(pl[i].x, pl[i].y, pl[i].z); // Eigen::Vector3d vecs[2]; // for(int j=0; j<2; j++) // { // int m = -1; // if(j == 1) // { // m = 1; // } // if(types[i+m].range < blind) // { // if(types[i].range > inf_bound) // { // types[i].edj[j] = Nr_inf; // } // else // { // types[i].edj[j] = Nr_blind; // } // continue; // } // vecs[j] = Eigen::Vector3d(pl[i+m].x, pl[i+m].y, pl[i+m].z); // vecs[j] = vecs[j] - vec_a; // types[i].angle[j] = vec_a.dot(vecs[j]) / vec_a.norm() / vecs[j].norm(); // if(types[i].angle[j] < jump_up_limit) // { // types[i].edj[j] = Nr_180; // } // else if(types[i].angle[j] > jump_down_limit) // { // types[i].edj[j] = Nr_zero; // } // } // types[i].intersect = vecs[Prev].dot(vecs[Next]) / vecs[Prev].norm() / vecs[Next].norm(); // if(types[i].edj[Prev]==Nr_nor && types[i].edj[Next]==Nr_zero && types[i].dista>0.0225 && types[i].dista>4*types[i-1].dista) // { // if(types[i].intersect > cos160) // { // if(edge_jump_judge(pl, types, i, Prev)) // { // types[i].ftype = Edge_Jump; // } // } // } // else if(types[i].edj[Prev]==Nr_zero && types[i].edj[Next]== Nr_nor && types[i-1].dista>0.0225 && types[i-1].dista>4*types[i].dista) // { // if(types[i].intersect > cos160) // { // if(edge_jump_judge(pl, types, i, Next)) // { // types[i].ftype = Edge_Jump; // } // } // } // else if(types[i].edj[Prev]==Nr_nor && types[i].edj[Next]==Nr_inf) // { // if(edge_jump_judge(pl, types, i, Prev)) // { // types[i].ftype = Edge_Jump; // } // } // else if(types[i].edj[Prev]==Nr_inf && types[i].edj[Next]==Nr_nor) // { // if(edge_jump_judge(pl, types, i, Next)) // { // types[i].ftype = Edge_Jump; // } // } // else if(types[i].edj[Prev]>Nr_nor && types[i].edj[Next]>Nr_nor) // { // if(types[i].ftype == Nor) // { // types[i].ftype = Wire; // } // } // } plsize2 = plsize-1; double ratio; for(uint i=head+1; i types[i].dista) { ratio = types[i-1].dista / types[i].dista; } else { ratio = types[i].dista / types[i-1].dista; } if(types[i].intersect &pl, ros::Publisher pub, const ros::Time &ct) { pl.height = 1; pl.width = pl.size(); sensor_msgs::PointCloud2 output; pcl::toROSMsg(pl, output); output.header.frame_id = "livox"; output.header.stamp = ct; pub.publish(output); } int plane_judge(const pcl::PointCloud &pl, vector &types, uint i_cur, uint &i_nex, Eigen::Vector3d &curr_direct) { double group_dis = disA*types[i_cur].range + disB; group_dis = group_dis * group_dis; // i_nex = i_cur; double two_dis; vector disarr; disarr.reserve(20); for(i_nex=i_cur; i_nex= group_dis) { break; } disarr.push_back(types[i_nex].dista); i_nex++; } double leng_wid = 0; double v1[3], v2[3]; for(uint j=i_cur+1; j leng_wid) { leng_wid = lw; } } if((two_dis*two_dis/leng_wid) < p2l_ratio) { curr_direct.setZero(); return 0; } uint disarrsize = disarr.size(); for(uint j=0; j=limit_maxmid || dismid_min>=limit_midmin) { curr_direct.setZero(); return 0; } } else { double dismax_min = disarr[0] / disarr[disarrsize-2]; if(dismax_min >= limit_maxmin) { curr_direct.setZero(); return 0; } } curr_direct << vx, vy, vz; curr_direct.normalize(); return 1; } bool edge_jump_judge(const pcl::PointCloud &pl, vector &types, uint i, Surround nor_dir) { if(nor_dir == 0) { if(types[i-1].rangeedgea*d2 || (d1-d2)>edgeb) { return false; } return true; } int plane_judge1(const pcl::PointCloud &pl, vector &types, uint i, uint &i_nex, Eigen::Vector3d &curr_direct) { double group_dis = 0.01*pl[i].x + 0.1; group_dis = group_dis*group_dis; double two_dis; vector disarr; disarr.reserve(128); for(i_nex=i; i_nex= group_dis) { break; } disarr.push_back(types[i_nex].dista); i_nex++; } double leng_wid = 0; double v1[3], v2[3]; for(uint j=i+1; j leng_wid) { leng_wid = lw; } } // if((two_dis*two_dis/leng_wid) <= 225) if((two_dis*two_dis/leng_wid) <= 400) { curr_direct = Eigen::Vector3d::Zero(); return 0; } // 寻找中位数(不是准确的中位数,有点偏差) for(uint32_t j=0; j=9 || dismid_min>=16) { curr_direct = Eigen::Vector3d::Zero(); return 0; } curr_direct << vx, vy, vz; curr_direct.normalize(); return 1; } bool edge_jump_judge1(const pcl::PointCloud &pl, vector &types, uint i, Surround nor_dir) { // if(nor_dir == 0) // { // if(pl[i-1].x0.05) { if(d1>3*d2 || (d1-d2)>0.05) { return false; } } return true; }