-
Notifications
You must be signed in to change notification settings - Fork 81
/
test_200_slam_ros1_hector.launch
63 lines (63 loc) · 3.6 KB
/
test_200_slam_ros1_hector.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
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
<?xml version="1.0"?>
<launch>
<!-- Transformation to see cloud-data in rviz -->
<node pkg="tf" type="static_transform_publisher" name="laser_baselaser" args="0 0 0 0 0 0 1 base_laser laser 100"/>
<!-- Transformation to prepare SLAM -->
<node pkg="tf" type="static_transform_publisher" name="cloud_base_laser"
args="0 0 0 0 0 0 1 base_laser cloud 100"/>
<node pkg="tf" type="static_transform_publisher" name="laserscan_layer_0_base_laser"
args="0 0 0 0 0 0 1 base_laser cloud_POS_000_DIST1 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_laser_to_base_link"
args="0 0 0 0 0 0 1 base_link base_laser 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_link_to_base_footprint"
args="0 0 0 0 0 0 1 base_footprint base_link 100"/>
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_odom"
args="0 0 0 0 0 0 1 odom base_footprint 100"/>
<node pkg="tf" type="static_transform_publisher" name="odom_to_scanmatcher"
args="0 0 0 0 0 0 1 scanmatcher_frame odom 100"/>
<arg name="tf_map_scanmatch_transform_frame_name" default="/scanmatcher_frame"/>
<arg name="base_frame" default="base_link"/>
<arg name="odom_frame" default="base_link"/>
<arg name="pub_map_odom_transform" default="true"/>
<arg name="scan_subscriber_queue_size" default="5"/>
<arg name="scan_topic" default="scan"/>
<arg name="map_size" default="2048"/>
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<!-- Frame names -->
<param name="map_frame" value="map"/>
<param name="base_frame" value="$(arg base_frame)"/>
<param name="odom_frame" value="$(arg base_frame)"/>
<!-- Tf use -->
<param name="use_tf_scan_transformation" value="true"/>
<param name="use_tf_pose_start_estimate" value="false"/>
<param name="pub_map_odom_transform" value="$(arg pub_map_odom_transform)"/>
<!-- Map size / start point -->
<param name="map_resolution" value="0.050"/>
<param name="map_size" value="$(arg map_size)"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5"/>
<param name="map_multi_res_levels" value="2"/>
<!-- 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.2"/>
<param name="map_update_angle_thresh" value="0.9"/>
<param name="laser_z_min_value" value="-1.0"/>
<param name="laser_z_max_value" value="1.0"/>
<!-- Advertising config -->
<param name="advertise_map_service" value="true"/>
<param name="scan_subscriber_queue_size" value="$(arg scan_subscriber_queue_size)"/>
<param name="scan_topic" value="$(arg scan_topic)"/>
<!-- Debug parameters -->
<!--
<param name="output_timing" value="false"/>
<param name="pub_drawings" value="true"/>
<param name="pub_debug_output" value="true"/>
-->
<param name="tf_map_scanmatch_transform_frame_name" value="$(arg tf_map_scanmatch_transform_frame_name)"/>
</node>
<!--<node pkg="tf" type="static_transform_publisher" name="map_nav_broadcaster" args="0 0 0 0 0 0 map nav 100"/>-->
<!--<arg name="rviz" default="true"/>-->
<!--<arg name="rviz_file" default="$(find sick_scan)/launch/rviz/hector.rviz"/>-->
<!--<node pkg="rviz" type="rviz" name="$(anon rviz)" args="-d $(arg rviz_file)" output="screen" if="$(arg rviz)"/>-->
</launch>