Add sample & test for features/normal_3d.cpp
This commit is contained in:
parent
87e7555655
commit
3e5c704046
@ -200,8 +200,9 @@ if(CATKIN_ENABLE_TESTING)
|
|||||||
find_package(rostest REQUIRED)
|
find_package(rostest REQUIRED)
|
||||||
add_rostest_gtest(test_tf_message_filter_pcl tests/test_tf_message_filter_pcl.launch src/test/test_tf_message_filter_pcl.cpp)
|
add_rostest_gtest(test_tf_message_filter_pcl tests/test_tf_message_filter_pcl.launch src/test/test_tf_message_filter_pcl.cpp)
|
||||||
target_link_libraries(test_tf_message_filter_pcl ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
|
target_link_libraries(test_tf_message_filter_pcl ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
|
||||||
add_rostest(samples/sample_statistical_outlier_removal.launch ARGS gui:=false)
|
add_rostest(samples/pcl_ros/features/sample_normal_3d.launch ARGS gui:=false)
|
||||||
add_rostest(samples/sample_voxel_grid.launch ARGS gui:=false)
|
add_rostest(samples/pcl_ros/filters/sample_statistical_outlier_removal.launch ARGS gui:=false)
|
||||||
|
add_rostest(samples/pcl_ros/filters/sample_voxel_grid.launch ARGS gui:=false)
|
||||||
endif(CATKIN_ENABLE_TESTING)
|
endif(CATKIN_ENABLE_TESTING)
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
44
pcl_ros/samples/pcl_ros/features/sample_normal_3d.launch
Normal file
44
pcl_ros/samples/pcl_ros/features/sample_normal_3d.launch
Normal file
@ -0,0 +1,44 @@
|
|||||||
|
<launch>
|
||||||
|
|
||||||
|
<arg name="gui" default="true" />
|
||||||
|
|
||||||
|
<!-- use voxel_grid for small cpu load in filtering -->
|
||||||
|
<include file="$(find pcl_ros)/samples/pcl_ros/filters/sample_voxel_grid.launch">
|
||||||
|
<arg name="gui" value="false" />
|
||||||
|
<arg name="test" value="false" />
|
||||||
|
<arg name="leaf_size" value="0.02" />
|
||||||
|
</include>
|
||||||
|
|
||||||
|
<node name="normal_estimation"
|
||||||
|
pkg="nodelet" type="nodelet"
|
||||||
|
args="standalone pcl/NormalEstimation">
|
||||||
|
<remap from="~input" to="voxel_grid/output" />
|
||||||
|
<rosparam>
|
||||||
|
radius_search: 0
|
||||||
|
k_search: 10
|
||||||
|
# 0, => ANN, 1 => FLANN, 2 => Organized
|
||||||
|
spatial_locator: 1
|
||||||
|
</rosparam>
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<test test-name="test_normal_estimation"
|
||||||
|
name="test_normal_estimation"
|
||||||
|
pkg="rostest" type="hztest">
|
||||||
|
<rosparam>
|
||||||
|
topic: /normal_estimation/output
|
||||||
|
hz: 10
|
||||||
|
hzerror: 8
|
||||||
|
test_duration: 5.0
|
||||||
|
</rosparam>
|
||||||
|
</test>
|
||||||
|
|
||||||
|
<!-- TODO(wkentaro): Add sample visualization
|
||||||
|
<group if="$(arg gui)">
|
||||||
|
<node name="rviz"
|
||||||
|
pkg="rviz" type="rviz"
|
||||||
|
args="-d $(find pcl_ros)/samples/pcl_ros/filters/config/normal_estimation.rviz">
|
||||||
|
</node>
|
||||||
|
</group>
|
||||||
|
-->
|
||||||
|
|
||||||
|
</launch>
|
||||||
Loading…
x
Reference in New Issue
Block a user