diff --git a/sciurus17_examples/README.md b/sciurus17_examples/README.md index 2358860..cec0bd2 100644 --- a/sciurus17_examples/README.md +++ b/sciurus17_examples/README.md @@ -211,7 +211,8 @@ ros2 launch sciurus17_examples chest_camera_tracking.launch.py 点群から物体を検出して掴むコード例です。 検出された物体位置はtfのフレームとして配信されます。 -tfの`frame_id`は検出された順に`target_0`、`target_1`、`target_2`…に設定されます。掴む対象は`target_0`に設定されています。 +tfの`frame_id`は検出された順に`target_0`、`target_1`、`target_2`…に設定されます。 +掴む対象はSciurus17前方の0.3 mの範囲にある`target_0`に設定されています。 物体検出には[Point Cloud Library](https://pointclouds.org/)を使用しています。 次のコマンドを実行します diff --git a/sciurus17_examples/src/point_cloud_detection.cpp b/sciurus17_examples/src/point_cloud_detection.cpp index 5a82277..879d6d6 100644 --- a/sciurus17_examples/src/point_cloud_detection.cpp +++ b/sciurus17_examples/src/point_cloud_detection.cpp @@ -130,7 +130,7 @@ class PointCloudSubscriber : public rclcpp::Node bool preprocessing(std::shared_ptr> & cloud) { - // X軸方向0.08~0.3m以外の点群を削除 + // X軸方向0.08~0.5m以外の点群を削除 pcl::PassThrough pass; pass.setInputCloud(cloud); pass.setFilterFieldName("x");