聚类时过滤点云
为过滤车体和车体旁可能影响规划的障碍物,在lidar_euclidean_cluster_detect功能包中新增filteredPointsBydistance函数。
void filteredPointsBydistance(const pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud_ptr,
pcl::PointCloud<pcl::PointXYZ>::Ptr out_cloud_ptr)
{
// 清空输出点云中的点
out_cloud_ptr->points.clear();
// 遍历输入点云中的每一个点
for (unsigned int i = 0; i < in_cloud_ptr->points.size(); i++)
{
// 检查点是否在设定的范围内(车辆的前、后、左、右范围)
if (in_cloud_ptr->points[i].x < _lidar_front_car_range && // 点的 x 值小于前方激光雷达范围
in_cloud_ptr->points[i].x > -_lidar_back_car_range && // 点的 x 值大于后方激光雷达范围
in_cloud_ptr->points[i].y < _lidar_left_car_range && // 点的 y 值小于左侧激光雷达范围
in_cloud_ptr->points[i].y > -_lidar_right_car_range) // 点的 y 值大于右侧激光雷达范围
continue; // 如果点在范围内,跳过该点
// 检查点是否在一个特定的小区域内
if (in_cloud_ptr->points[i].x < 0.2 && // 点的 x 值小于 0.2
in_cloud_ptr->points[i].x > 0.0 && // 点的 x 值大于 0.0
in_cloud_ptr->points[i].y < -0.5 && // 点的 y 值小于 -0.5
in_cloud_ptr->points[i].y > -0.9 && // 点的 y 值大于 -0.9
in_cloud_ptr->points[i].z > -0.4 && // 点的 z 值大于 -0.4
in_cloud_ptr->points[i].z < 0.0) // 点的 z 值小于 0.0
continue; // 如果点在此小区域内,跳过该点
// 如果点不在上述范围,添加到输出点云中
out_cloud_ptr->points.push_back(in_cloud_ptr->points[i]);
}
}
在点云回调函数velodyne_callback中调用:
pcl::PointCloud<pcl::PointXYZ>::Ptr current_sensor_cloud_ptr(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud_ptr(new pcl::PointCloud<pcl::PointXYZ>);
autoware_msgs::Centroids centroids;
autoware_msgs::CloudClusterArray cloud_clusters;
pcl::fromROSMsg(*in_sensor_cloud, *current_sensor_cloud_ptr);
_velodyne_header = in_sensor_cloud->header;
// 修改
filteredPointsBydistance(current_sensor_cloud_ptr, filtered_cloud_ptr);
浙公网安备 33010602011771号