WUT Velma robot API
octomap_server.launch
Go to the documentation of this file.
1 <?xml version="1.0"?>
2 <launch>
3  <arg name="use_hw_kinect" default="false"/>
4  <arg name="octomap_file" default=""/>
5  <arg name="resolution" default="0.04"/>
6 
7 
8  <arg unless="$(arg use_hw_kinect)" name="POINTCLOUD_TOPIC" value="/head_kinect/depth/points"/>
9  <arg if="$(arg use_hw_kinect)" name="POINTCLOUD_TOPIC" value="/head_kinect/depth_registered/points"/>
10 
11  <node pkg="pointcloud_utils" type="pc_filter" name="pc_filter" output="screen">
12  <param name="tolerance" value="0.1" />
13  <param name="horizontal_fov" value="1.047" />
14 
15  <remap from="cloud_in" to="$(arg POINTCLOUD_TOPIC)"/>
16  <remap from="cloud_out" to="/pc_filter/points"/>
17  <remap from="cloud_ex_out" to="/pc_filter/points_ex"/>
18  </node>
19 
20  <node name="om_server" pkg="octomap_server" type="octomap_server_node" output="screen" args="$(arg octomap_file)">
21  <param name="resolution" value="$(arg resolution)" />
22  <param name="frame_id" type="string" value="world" />
23  <param name="sensor_model/max_range" value="2.2" />
24  <param name="publish_free_space" value="true" />
25  <remap from="octomap_full" to="/om_server/octomap_full"/>
26  <remap from="octomap_binary" to="/om_server/octomap_binary"/>
27  <remap from="cloud_in" to="/pc_filter/points"/>
28  </node>
29  <node pkg="pointcloud_utils" type="octomap_filter" name="octomap_filter" output="screen">
30  <param name="resolution" value="0.08" />
31  <param name="xmin" value="-1.3" />
32  <param name="xmax" value="1.3" />
33  <param name="ymin" value="-1.3" />
34  <param name="ymax" value="1.3" />
35  <param name="zmin" value="0.0" />
36  <param name="zmax" value="2.0" />
37  <param name="visualize_unknown" value="true" />
38  <param name="visualize_merged" value="true" />
39  <remap from="octomap_full" to="/om_server/octomap_full"/>
40  <remap from="octomap_merged_binary" to="/octomap_binary"/>
41  </node>
42 
43 </launch>
44