-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathvoxblox.launch
38 lines (36 loc) · 1.85 KB
/
voxblox.launch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="robot_name" default="X1" />
<arg name="voxel_size" default="0.2" />
<arg name="voxels_per_side" default="64" />
<arg name="world_frame" default="world" />
<group ns="$(arg robot_name)">
<node name="voxblox_node" pkg="voxblox_ros" type="esdf_server" output="screen" args="-alsologtostderr" clear_params="true">
<!-- <remap from="pointcloud" to="/$(arg robot_name)/points"/> -->
<!-- <remap from="pointcloud" to="points_filtered"/> -->
<remap from="pointcloud" to="octomap_in"/>
<remap from="voxblox_node/esdf_map_out" to="esdf_map" />
<!-- <param name="truncation_distance" value="4.0"/> -->
<param name="voxel_carving_enabled" value="true"/>
<param name="tsdf_voxel_size" value="$(arg voxel_size)" />
<param name="tsdf_voxels_per_side" value="$(arg voxels_per_side)" />
<param name="max_ray_length_m" value="7.0" />
<param name="allow_clear" value="true"/>
<param name="publish_esdf_map" value="true" />
<param name="esdf_max_distance_m" value="10.0"/>
<param name="publish_pointclouds" value="true" />
<param name="publish_traversable" value="true" />
<param name="publish_slices" value="true" />
<param name="slice_level" value="0.6" />
<param name="use_tf_transforms" value="true" />
<param name="update_mesh_every_n_sec" value="0.5" />
<param name="clear_sphere_for_planning" value="false" />
<param name="world_frame" value="$(arg world_frame)" />
<param name="sensor_frame" value="/$(arg robot_name)/front_laser" />
<!-- <param name="enable_icp" value="true" /> -->
<!-- <param name="icp_refine_roll_pitch" value="false" /> -->
<!-- <param name="max_block_distance_from_body" value="30.0" /> -->
<param name="verbose" value="false" />
</node>
</group>
</launch>