-
Notifications
You must be signed in to change notification settings - Fork 51
/
Copy pathmove_base_template.launch
180 lines (114 loc) · 6.32 KB
/
move_base_template.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
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
<launch>
<master auto="start"/>
<!-- Launch MongoDB map server. Note: All the maps must be preloaded into the Database -->
<include file="$(find multi_map_navigation)/launch/setup/mongodb_server.launch">
<arg name="host" value="localhost"/>
<arg name="port" value="27017"/>
<arg name="db_overwrite" value="true"/>
<arg name="db_location" value="warehouse_data"/>
</include>
<!-- Use the following group as a template for spawning multiple robots. Note: You should put your config files inside /config/robot# -->
<group ns="robot0">
<!-- Name - Must be consistent with spawn name [To edit]: -->
<!-- |||||||||||||||||||||||||||||||| -->
<arg name="modelName" value="robot0"/>
<!-- |||||||||||||||||||||||||||||||| -->
<!-- Launch elevator manager -->
<node pkg="multi_map_navigation" type="elevator_manager.py" name="elevator_blast" output="screen"/>
<param name="tf_prefix" value="$(arg modelName)" />
<!-- Launch map_store with MongoDB contents -->
<include file="$(find multi_map_navigation)/launch/setup/map_store.launch">
<arg name="frame_id_ref" value="$(arg modelName)/map"/>
</include>
<!-- Move base: -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<!-- <remap from="cmd_vel" to="/$(arg modelName)/cmd_vel"/> -->
<remap from="map" to="map_store_map"/>
<rosparam file="$(find <navigation_stack>)/config/$(arg modelName)/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find <navigation_stack>)/config/$(arg modelName)/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find <navigation_stack>)/config/$(arg modelName)/local_costmap_params.yaml" command="load" />
<rosparam file="$(find <navigation_stack>)/config/$(arg modelName)/global_costmap_params.yaml" command="load" />
<rosparam file="$(find <navigation_stack>)/config/$(arg modelName)/base_local_planner_params.yaml" command="load" />
<param name="controller_frequency" value="20.0" />
</node>
<node pkg="multi_map_navigation" type="multi_map_navigation_manager.py" name="multi_map_navigation" output="screen">
<param name="definition_file" value="$(find <navigation_stack>)/config/multi_level_db/cfg.yaml" />
<param name="transition_types" value="elevator_blast" />
<param name="robot_namespace" value="$(arg modelName)"/>
<param name="base_frame" value="base_link"/>
</node>
<!-- AMCL: -->
<include file="$(find <navigation_stack>)/launch/amcl.launch">
<arg name="botName" value="$(arg modelName)"/>
</include>
</group>
<group ns="robot1">
<!-- Name - Must be consistent with spawn name [To edit]: -->
<!-- |||||||||||||||||||||||||||||||| -->
<arg name="modelName" value="robot1"/>
<!-- |||||||||||||||||||||||||||||||| -->
<!-- Launch elevator manager -->
<node pkg="multi_map_navigation" type="elevator_manager.py" name="elevator_blast" output="screen"/>
<param name="tf_prefix" value="$(arg modelName)" />
<!-- Launch map_store with MongoDB contents -->
<include file="$(find multi_map_navigation)/launch/setup/map_store.launch">
<arg name="frame_id_ref" value="$(arg modelName)/map"/>
</include>
<!-- Move base: -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<!-- <remap from="cmd_vel" to="/$(arg modelName)/cmd_vel"/> -->
<remap from="map" to="map_store_map"/>
<rosparam file="$(find <navigation_stack>)/config/$(arg modelName)/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find <navigation_stack>)/config/$(arg modelName)/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find <navigation_stack>)/config/$(arg modelName)/local_costmap_params.yaml" command="load" />
<rosparam file="$(find <navigation_stack>)/config/$(arg modelName)/global_costmap_params.yaml" command="load" />
<rosparam file="$(find <navigation_stack>)/config/$(arg modelName)/base_local_planner_params.yaml" command="load" />
<param name="controller_frequency" value="20.0" />
</node>
<node pkg="multi_map_navigation" type="multi_map_navigation_manager.py" name="multi_map_navigation" output="screen">
<param name="definition_file" value="$(find <navigation_stack>)/config/multi_level_db/cfg.yaml" />
<param name="transition_types" value="elevator_blast" />
<param name="robot_namespace" value="$(arg modelName)"/>
<param name="base_frame" value="base_link"/>
</node>
<!-- AMCL: -->
<include file="$(find <navigation_stack>)/launch/amcl.launch">
<arg name="botName" value="$(arg modelName)"/>
</include>
</group>
<!-- Setup RVIZ Mux: -->
<node name="namespace_mux" pkg="namespace_mux" type="namespace_mux" output="screen">
<rosparam param="/namespace_mux/robot_namespace_ref">"robot"</rosparam>
<rosparam param="/namespace_mux/rviz_namespace">"rviz"</rosparam>
<rosparam param="/namespace_mux/active_bots">[
"robot0", "robot1"
]</rosparam>
<rosparam param="/namespace_mux/subscribed_topics">[
"/map_store_map",
"/odom",
"/laser/merged",
"/laser/scan_back",
"/laser/scan_front",
"/move_base/local_costmap/obstacle_layer_footprint/footprint_stamped",
"/move_base/TrajectoryPlannerROS/local_plan",
"/move_base/local_costmap/costmap",
"/move_base/TrajectoryPlannerROS/global_plan",
"/wormhole_marker",
"/waiting_area_marker",
"/particlecloud"
]</rosparam>
<rosparam param="/namespace_mux/published_topics">[
"/cmd_vel",
"/initialpose",
"/move_base_simple/goal",
"/clicked_point"
]</rosparam>
</node>
<!-- Setup Fake Map-Frame ID -->
<node name="fake_tf_broadcaster" pkg="namespace_mux" type="fake_tf_broadcaster" output="screen">
<rosparam param="/fake_tf_broadcaster/pub_freq">50</rosparam>
<rosparam param="/fake_tf_broadcaster/input_curr_frame_ids">["robot0/map", "robot1/map"]</rosparam>
<rosparam param="/fake_tf_broadcaster/output_fake_frame_ids">["rviz/map"]</rosparam>
<rosparam param="/fake_tf_broadcaster/output_tf_offset">[0.0, 0.0, 0.0, 0.0, 0.0, 0.0]</rosparam>
</node>
</launch>