はじめに
ある点群から特定の法線方向の点群のみ抽出したいと思い調べたところ、jsk_pcl_ros
のNormalDirectionFilter
でそのような処理ができることがわかりました。
使ってみる
以下のパッケージで簡単にjsk_pcl_ros
のNormalDirectionFilter
を試すことができます。
install
sudo apt-get install -y ros-melodic-jsk-pcl-ros
sudo apt-get install -y ros-melodic-jsk-visualization
git clone https://github.com/hoshianaaa/jsk_pcl_ros_samples.git
cd ~/catkin_ws
catkin build
または
catkin make
source ~/catkin_ws/devel/setup.bash
実行
roslaunch jsk_pcl_ros_samples normal_direction_filter.launch
作成したlaunchは次のようになっていて赤枠部分のnodeletに法線点群を入力します。またパラメータとしてuse_imu=false
,eps_angle
,direction
を指定します。
launch
<launch>
<arg name="gui" default="true"/>
<include file="$(find jsk_pcl_ros_samples)/launch/normal_estimation_omp.launch">
<arg name="file_name" value="$(find jsk_pcl_ros_samples)/pcd/bunny.pcd"/>
<arg name="gui" default="false"/>
</include>
<node name="normal_direction_filter"
pkg="nodelet" type="nodelet"
args="standalone jsk_pcl/NormalDirectionFilter">
<remap from="~input" to="normal_estimation_omp/output"/>
<rosparam>
use_imu: false
eps_angle: 0.2
direction: [0, 0, 1]
</rosparam>
</node>
<group if="$(arg gui)">
<node name="extract_indices_normal_filtered"
pkg="nodelet" type="nodelet"
args="standalone jsk_pcl/ExtractIndices">
<remap from="~input" to="normal_estimation_omp/output_with_xyz"/>
<remap from="~indices" to="normal_direction_filter/output"/>
<rosparam>
keep_organized: true
</rosparam>
</node>
<node name="rviz"
pkg="rviz" type="rviz"
args="-d $(find jsk_pcl_ros_samples)/rviz/normal_direction_filter.rviz"/>
</group>
</launch>
結果
下の写真のように特定の方向の点群のみ抽出することができました。