Skip to content

Commit

Permalink
点群の取得範囲を修正
Browse files Browse the repository at this point in the history
  • Loading branch information
Kuwamai committed Oct 15, 2024
1 parent 81abda0 commit 3ea7866
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions sciurus17_examples/src/point_cloud_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,18 +130,18 @@ class PointCloudSubscriber : public rclcpp::Node

bool preprocessing(std::shared_ptr<pcl::PointCloud<pcl::PointXYZRGB>> & cloud)
{
// X軸方向0.05~0.5m以外の点群を削除
// X軸方向0.08~0.3m以外の点群を削除
pcl::PassThrough<pcl::PointXYZRGB> pass;
pass.setInputCloud(cloud);
pass.setFilterFieldName("x");
pass.setFilterLimits(0.05, 0.5);
pass.setFilterLimits(0.08, 0.5);
pass.filter(*cloud);

// Z軸方向0.03~0.5m以外の点群を削除
// Z軸方向0.03~0.2m以外の点群を削除
// 物体が乗っている平面の点群を削除します
pass.setInputCloud(cloud);
pass.setFilterFieldName("z");
pass.setFilterLimits(0.03, 0.5);
pass.setFilterLimits(0.03, 0.2);
pass.filter(*cloud);

// Voxel gridで点群を間引く(ダウンサンプリング)
Expand Down

0 comments on commit 3ea7866

Please sign in to comment.