Re: Using obstacles detection nodelet from camera node point cloud
Posted by
matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Using-obstacles-detection-nodelet-from-camera-node-point-cloud-tp1191p1197.html
Hi,
I tested obstacles_detection with your bag, and actually /ground_cloud and /obstacles_cloud are published, but at a very low rate (like 30 sec to process only one cloud).
To better test it, I put a VoxelFilter so that obstacles detection is done in ~20 ms:
<launch>
<node pkg="nodelet" type="nodelet" name="pcl_manager" args="manager" output="screen" />
<!-- Run a VoxelGrid filter to clean NaNs and downsample the data -->
<node pkg="nodelet" type="nodelet" name="voxel_grid" args="load pcl/VoxelGrid pcl_manager" output="screen">
<remap from="~input" to="/camera/point_cloud/cloud" />
<rosparam>
filter_field_name: z
filter_limit_min: -10
filter_limit_max: 10
filter_limit_negative: False
leaf_size: 0.05
</rosparam>
</node>
<node pkg="nodelet" type="nodelet" name="obstacles_detection" args="load rtabmap_ros/obstacles_detection pcl_manager" output="screen">
<remap from="cloud" to="/voxel_grid/output"/>
<remap from="obstacles" to="/obstacles_cloud"/>
<remap from="ground" to="/ground_cloud"/>
<param name="frame_id" type="string" value="base_link"/>
<param name="map_frame_id" type="string" value="map"/>
<param name="wait_for_transform" type="bool" value="true"/>
<param name="min_cluster_size" type="int" value="20"/>
<param name="max_obstacles_height" type="double" value="0.4"/>
</node>
</launch>
Output: