// // Created by zx on 2021/5/20. // #include "ground_region.h" #include #include #include #include #include //欧式聚类******************************************************* std::vector::Ptr> Ground_region::segmentation(pcl::PointCloud::Ptr sor_cloud) { std::vector ece_inlier; pcl::search::KdTree::Ptr tree(new pcl::search::KdTree); pcl::EuclideanClusterExtraction ece; ece.setInputCloud(sor_cloud); ece.setClusterTolerance(0.07); ece.setMinClusterSize(20); ece.setMaxClusterSize(20000); ece.setSearchMethod(tree); ece.extract(ece_inlier); std::vector::Ptr> segmentation_clouds; for (int i = 0; i < ece_inlier.size(); i++) { pcl::PointCloud::Ptr cloud_copy(new pcl::PointCloud); std::vector ece_inlier_ext = ece_inlier[i].indices; copyPointCloud(*sor_cloud, ece_inlier_ext, *cloud_copy); //按照索引提取点云数据 segmentation_clouds.push_back(cloud_copy); } return segmentation_clouds; } /** * @description: distance between two points * @param {Point2f} p1 * @param {Point2f} p2 * @return the distance */ double Ground_region::distance(cv::Point2f p1, cv::Point2f p2) { return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0)); } /** * @description: point rectangle detect * @param points detect if points obey the rectangle rule * @return wether forms a rectangle */ bool Ground_region::isRect(std::vector &points) { if (points.size() == 4) { double L[3] = {0.0}; L[0] = distance(points[0], points[1]); L[1] = distance(points[1], points[2]); L[2] = distance(points[0], points[2]); double max_l = L[0]; double l1 = L[1]; double l2 = L[2]; cv::Point2f ps = points[0], pt = points[1]; cv::Point2f pc = points[2]; for (int i = 1; i < 3; ++i) { if (L[i] > max_l) { max_l = L[i]; l1 = L[abs(i + 1) % 3]; l2 = L[abs(i + 2) % 3]; ps = points[i % 3]; pt = points[(i + 1) % 3]; pc = points[(i + 2) % 3]; } } //直角边与坐标轴的夹角 <20° float thresh = 20.0 * M_PI / 180.0; cv::Point2f vct(pt.x - pc.x, pt.y - pc.y); float angle = atan2(vct.y, vct.x); if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh))) { //std::cout<<" 4 wheel axis angle : "<= 0.15) { /*char description[255]={0}; sprintf(description,"angle cos value(%.2f) >0.13 ",cosa); std::cout< 1.900 || length > 3.300 || length < 2.200) { /*char description[255]={0}; sprintf(description,"width<1400 || width >1900 || length >3300 ||length < 2200 l:%.1f,w:%.1f",length,width); std::cout< max_l * 0.1 || distance(center1, center2) > 0.150) { /*std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2< max_l * 0.1 || distance(center1, center2) > 0.150 "); std::cout< max_l) { max_index = i; max_l = L[i]; l1 = L[abs(i + 1) % 3]; l2 = L[abs(i + 2) % 3]; ps = points[i % 3]; pt = points[(i + 1) % 3]; pc = points[(i + 2) % 3]; } } //直角边与坐标轴的夹角 <20° float thresh = 20.0 * M_PI / 180.0; cv::Point2f vct(pt.x - pc.x, pt.y - pc.y); float angle = atan2(vct.y, vct.x); if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh))) { //std::cout<<" 4 wheel axis angle : "<= 0.15) { /*char description[255]={0}; sprintf(description,"3 wheels angle cos value(%.2f) >0.13 ",cosa); std::cout< 2.100 && l < 3.300 && w > 1.400 && w < 2.100) { //生成第四个点 cv::Point2f vec1 = ps - pc; cv::Point2f vec2 = pt - pc; cv::Point2f point4 = (vec1 + vec2) + pc; points.push_back(point4); /*char description[255]={0}; sprintf(description,"3 wheels rectangle cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w); std::cout<::Ptr cloud, double thresh_z, detect_wheel_ceres3d::Detect_result &result) { if (m_detector == nullptr) return false; pcl::PointCloud::Ptr cloud_filtered(new pcl::PointCloud); for (int i = 0; i < cloud->size(); ++i) { pcl::PointXYZ pt = cloud->points[i]; if (pt.z < thresh_z) { cloud_filtered->push_back(pt); } } //下采样 pcl::VoxelGrid vox; //创建滤波对象 vox.setInputCloud(cloud_filtered); //设置需要过滤的点云给滤波对象 vox.setLeafSize(0.02f, 0.02f, 0.2f); //设置滤波时创建的体素体积为1cm的立方体 vox.filter(*cloud_filtered); //执行滤波处理,存储输出 if (cloud_filtered->size() == 0) { return false; } if (cloud_filtered->size() == 0) return false; pcl::StatisticalOutlierRemoval sor; //创建滤波器对象 sor.setInputCloud(cloud_filtered); //设置待滤波的点云 sor.setMeanK(5); //设置在进行统计时考虑的临近点个数 sor.setStddevMulThresh(3.0); //设置判断是否为离群点的阀值,用来倍乘标准差,也就是上面的std_mul sor.filter(*cloud_filtered); //滤波结果存储到cloud_filtered if (cloud_filtered->size() == 0) { return false; } std::vector::Ptr> seg_clouds; seg_clouds = segmentation(cloud_filtered); if (!(seg_clouds.size() == 4 || seg_clouds.size() == 3)) { return false; } std::vector centers; for (int i = 0; i < seg_clouds.size(); ++i) { Eigen::Vector4f centroid; pcl::compute3DCentroid(*seg_clouds[i], centroid); centers.push_back(cv::Point2f(centroid[0], centroid[1])); } bool ret = isRect(centers); if (ret) { std::string error_str; if (m_detector->detect(seg_clouds, result, error_str)) { return true; } else { return false; } } return ret; } // constructor Ground_region::Ground_region() { m_detector = nullptr; m_measure_thread = nullptr; } // deconstructor Ground_region::~Ground_region() { if(m_measure_thread){ m_measure_condition.kill_all(); // Close Capturte Thread if (m_measure_thread->joinable()) { m_measure_thread->join(); delete m_measure_thread; m_measure_thread = nullptr; } } } Error_manager Ground_region::init(velodyne::Region region) { m_region = region; m_measure_thread = new std::thread(&Ground_region::thread_measure_func, this); return SUCCESS; } // 计算均方误差 bool computer_var(std::vector data, double &var) { if (data.size() == 0) return false; Eigen::VectorXd dis_vec(data.size()); for (int i = 0; i < data.size(); ++i) { dis_vec[i] = data[i]; } double mean = dis_vec.mean(); Eigen::VectorXd mean_vec(data.size()); Eigen::VectorXd mat = dis_vec - (mean_vec.setOnes() * mean); Eigen::MatrixXd result = (mat.transpose()) * mat; var = sqrt(result(0) / double(data.size())); return true; } Error_manager Ground_region::detect(pcl::PointCloud::Ptr cloud, detect_wheel_ceres3d::Detect_result &last_result) { if (cloud->size() == 0) return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "no point"); pcl::PointCloud::Ptr cloud_filtered(new pcl::PointCloud); for (int i = 0; i < cloud->size(); ++i) { pcl::PointXYZ pt = cloud->points[i]; if (pt.x > m_region.minx() && pt.x < m_region.maxx() && pt.y > m_region.miny() && pt.y < m_region.maxy() && pt.z > m_region.minz() && pt.z < m_region.maxz()) { cloud_filtered->push_back(pt); } } if (cloud_filtered->size() == 0) return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "filtered no point"); float start_z = m_region.minz(); float max_z = 0.2; float center_z = (start_z + max_z) / 2.0; float last_center_z = start_z; float last_succ_z = -1.0; int count = 0; //二分法 找识别成功的 最高的z std::vector results; do { detect_wheel_ceres3d::Detect_result result; bool ret = classify_ceres_detect(cloud_filtered, center_z, result); // std::cout << "z: " << center_z <<", "< 0.01); // if (results.size() == 0) { return Error_manager(FAILED, NORMAL, "no car detected"); } /// to be float min_mean_loss = 1.0; for (int i = 0; i < results.size(); ++i) { detect_wheel_ceres3d::Detect_result result = results[i]; std::vector loss; loss.push_back(result.loss.lf_loss); loss.push_back(result.loss.rf_loss); loss.push_back(result.loss.lb_loss); loss.push_back(result.loss.rb_loss); double mean = (result.loss.lf_loss + result.loss.rf_loss + result.loss.lb_loss + result.loss.rb_loss) / 4.0; double var = -1.; computer_var(loss, var); if (mean < min_mean_loss) { last_result = result; min_mean_loss = mean; } } printf("z : %.3f angle : %.3f front : %.3f wheel_base:%.3f,width:%.3f, mean:%.5f\n", center_z, last_result.theta, last_result.front_theta, last_result.wheel_base, last_result.width, min_mean_loss); //m_detector->save_debug_data("/home/zx/zzw/catkin_ws/src/feature_extra/debug"); return SUCCESS; } #include "message/message_base.pb.h" void Ground_region::thread_measure_func() { //保持 10 fps while (m_measure_condition.is_alive()) { m_measure_condition.wait(); if (m_measure_condition.is_alive()) { // to be 发布结果 msg.set_ground_statu(message::Car_correct); message::Locate_information locate_information; locate_information.set_locate_x(result.cx); locate_information.set_locate_y(result.cy); locate_information.set_locate_angle(result.theta); locate_information.set_locate_wheel_base(result.wheel_base); locate_information.set_locate_length(result.wheel_base); locate_information.set_locate_wheel_width(result.width); locate_information.set_locate_width(result.body_width); locate_information.set_locate_front_theta(result.front_theta); locate_information.set_locate_correct(true); Communication_message c_msg; c_msg.reset(msg.base_info(), msg.SerializeAsString()); Publisher::get_instance_pointer()->publish_msg(&c_msg); } } }