6 http://wiki.ros.org/hector_slam/Tutorials/SettingUpForYourRobot
7 https://github.com/uenota/f550_launch_odroid/wiki/mapping_default.launch
11 <arg name="tf_map_scanmatch_transform_frame_name" default="scanmatcher_frame"/>
12 <arg name="base_frame" default="fcu"/>
13 <arg name="odom_frame" default="fcu"/>
14 <arg name="pub_map_odom_transform" default="true"/>
15 <arg name="scan_subscriber_queue_size" default="5"/>
16 <arg name="scan_topic" default="laser/scan"/>
17 <arg name="map_size" default="2048"/>
19 <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
22 <param name="map_frame" value="map" />
23 <param name="base_frame" value="$(arg base_frame)" />
24 <param name="odom_frame" value="$(arg odom_frame)" />
27 <param name="use_tf_scan_transformation" value="true"/>
28 <param name="use_tf_pose_start_estimate" value="false"/>
29 <param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>
31 <!-- Map size / start point -->
32 <param name="map_resolution" value="0.050"/>
33 <param name="map_size" value="$(arg map_size)"/>
34 <param name="map_start_x" value="0.5"/>
35 <param name="map_start_y" value="0.5" />
36 <param name="map_multi_res_levels" value="2" />
38 <!-- Map update parameters -->
39 <param name="update_factor_free" value="0.4"/>
40 <param name="update_factor_occupied" value="0.9" />
41 <param name="map_update_distance_thresh" value="0.4"/>
42 <param name="map_update_angle_thresh" value="0.06" />
43 <param name="laser_z_min_value" value = "-1.0" />
44 <param name="laser_z_max_value" value = "1.0" />
46 <!-- Advertising config -->
47 <param name="advertise_map_service" value="true"/>
49 <param name="scan_subscriber_queue_size" value="$(arg scan_subscriber_queue_size)"/>
50 <param name="scan_topic" value="$(arg scan_topic)"/>
52 <!-- Debug parameters -->
54 <param name="output_timing" value="false"/>
55 <param name="pub_drawings" value="true"/>
56 <param name="pub_debug_output" value="true"/>
58 <param name="tf_map_scanmatch_transform_frame_name" value="$(arg tf_map_scanmatch_transform_frame_name)" />
61 <!--<node pkg="tf" type="static_transform_publisher" name="map_nav_broadcaster" args="0 0 0 0 0 0 map nav 100"/>-->