-
Notifications
You must be signed in to change notification settings - Fork 0
/
igvcnavigation.launch
111 lines (82 loc) · 4.25 KB
/
igvcnavigation.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
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
<launch>
<master auto="start"/>
<!-- Run the map server -->
<!--node name="map_server" pkg="map_server" type="map_server" args="$(find my_map_package)/my_map.pgm my_map_resolution"/-->
<!-- Run Hector Slam -->
<!--node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<param name="scan_topic" value="/laser_scan" />
<param name="base_frame" value="base_footprint" />
<param name="output_timing" value="false"/>
<param name="use_tf_scan_transformation" value="true"/>
<param name="use_tf_pose_start_estimate" value="false"/>
<param name="map_pub_period" value="1.0"/>
<param name="laser_z_min_value" value = "-0.3"/>
<param name="update_factor_free" value="0.3"/>
<param name="map_resolution" value="0.05"/>
<param name="map_size" value="1024"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5"/>
<param name="map_multi_res_levels" value="1"/>
</node-->
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<!-- Topic names -->
<param name="scan_topic" value="laser_scan" />
<param name="map_frame" value="map" />
<param name="base_frame" value="base_footprint" />
<!-- <param name="odom_frame" value="odom"/> -->
<param name="odom_frame" value="base_footprint"/>
<param name="output_timing" value="false"/>
<!--
<param name="scan_topic" value="laser_scan" />
<param name="map_frame" value="map" />
<param name="base_frame" value="hokuyo_link" />
<param name="odom_frame" value="hokuyo_link"/>
<param name="output_timing" value="false"/>
-->
<!-- 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="true"/>
<param name="advertise_map_service" value="true"/>
<!-- Map size / start point -->
<param name="map_resolution" value="0.050"/>
<param name="map_size" value="1024"/>
<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.9" />
<param name="map_update_distance_thresh" value="0.4"/>
<param name="map_update_angle_thresh" value="0.06" />
<!-- Debug parameters -->
<!--
<param name="pub_drawings" value="true"/>
<param name="pub_debug_output" value="true"/>
-->
</node>
<node pkg="hector_trajectory_server" type="hector_trajectory_server" name="hector_trajectory_server" output="screen">
<param name="target_frame_name" type="string" value="/map" />
<param name="source_frame_name" type="string" value="/base_footprint" /><!-- hokuyo_link -->
<param name="trajectory_update_rate" type="double" value="4" />
<param name="trajectory_publish_rate" type="double" value="0.25" />
</node>
<node pkg="hector_geotiff" type="geotiff_node" name="hector_geotiff_node" output="screen" launch-prefix="nice -n 15">
<remap from="map" to="/dynamic_map" />
<param name="map_file_path" type="string" value="$(find hector_geotiff)/maps" />
<param name="map_file_base_name" type="string" value="hector_slam_map" />
<param name="geotiff_save_period" type="double" value="10" />
<param name="draw_background_checkerboard" type="bool" value="true" />
<param name="draw_free_space_grid" type="bool" value="true" />
</node>
<!--- Run AMCL -->
<include file="$(find amcl)/examples/amcl_omni.launch" />
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="footprint_padding" value="0.05" />
<rosparam file="$(find igvc_2dnav)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find igvc_2dnav)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find igvc_2dnav)/config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find igvc_2dnav)/config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find igvc_2dnav)/config/base_local_planner_params.yaml" command="load" />
</node>
</launch>