Skip to content

Commit bc6145a

Browse files
committed
add: 设置在过滤字段上的范围(-3.0~1.0
1 parent 8065860 commit bc6145a

1 file changed

Lines changed: 2 additions & 2 deletions

File tree

  • object_tracking/src/groundremove

‎object_tracking/src/groundremove/main.cpp‎

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -105,7 +105,7 @@ void cloud_cb(const sensor_msgs::PointCloud2ConstPtr &input)
105105
pcl::PassThrough<pcl::PointXYZ> pass; //设置滤波器对象
106106
pass.setInputCloud(cloud); //设置输���点云cloud(由input转化而来)
107107
pass.setFilterFieldName("z"); //设置过滤时所需要点云类型的z字段
108-
pass.setFilterLimits(filter_z_min, filter_z_max); //设置在过滤字段上的范围
108+
pass.setFilterLimits(filter_z_min, filter_z_max); //设置在过滤字段上的范围(-3.0~1.0)
109109
//pass.setFilterLimitsNegative (true); //设置保留范围内的还是过滤掉范围内的
110110
pass.filter(*z_filter_cloud); //执行滤波,保存过滤结果在cloud_filtered
111111

@@ -144,7 +144,7 @@ int main(int argc, char **argv)
144144
//订阅者 : "velodyne_points" "/kitti/velo/pointcloud" --话题名(可以根据不同数据集修改话题名) cloud_cb--回调函数
145145
// ros::Subscriber sub = nh.subscribe("/kitti/velo/pointcloud", 160, cloud_cb);
146146
ros::Subscriber sub = nh.subscribe("velodyne_points", 160, cloud_cb);
147-
nh.param<float>("filter_z_max", filter_z_max, 1.0); // 参数服务器默认参数
147+
nh.param<float>("filter_z_max", filter_z_max, 1.0); // 参数服务器默认参数(z轴上的滤波)
148148
nh.param<float>("filter_z_min", filter_z_min, -3.0); // nh.param<std::string>("default_param", default_param, "default_value");
149149
filter_mid_area_limitation(); // //创建条件限定下的滤波器
150150

0 commit comments

Comments
 (0)