-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathmapping-simple.launch
More file actions
34 lines (29 loc) · 1.4 KB
/
mapping-simple.launch
File metadata and controls
34 lines (29 loc) · 1.4 KB
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
<?xml version="1.0"?>
<launch>
<node pkg="tf" type="static_transform_publisher" name="laser" args="0 0 0 0 ${pi} 0 base_link laser 100" />
<node pkg="urg_node" type="urg_node" name="urg_node" args="/dev/ttyACM0"/>
<node name="rviz" pkg="rviz" type="rviz" />
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<param name="base_frame" value="base_link" />
<param name="odom_frame" value="base_link"/>
<param name="output_timing" value="false"/>
<param name="use_tf_scan_transformation" value="false"/>
<param name="use_tf_pose_start_estimate" value="false"/>
<param name="scan_topic" value="scan"/>
<!-- Map size / start point -->
<param name="map_resolution" value="0.025"/>
<param name="map_size" value="2048"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5" />
<!--param name="laser_z_min_value" value="-2.5" /-->
<!--param name="laser_z_max_value" value="3.5" /-->
<!-- Map update parameters -->
<param name="update_factor_free" value="0.4"/>
<param name="update_factor_occupied" value="0.7" />
<param name="map_update_distance_thresh" value="0.6"/>
<param name="map_update_angle_thresh" value="0.9" />
<param name="pub_map_odom_transform" value="true"/>
<param name="pub_drawings" value="true"/>
<param name="pub_debug_output" value="true"/>
</node>
</launch>