-
Notifications
You must be signed in to change notification settings - Fork 2
Expand file tree
/
Copy pathmove_base.launch
More file actions
39 lines (31 loc) · 2.24 KB
/
move_base.launch
File metadata and controls
39 lines (31 loc) · 2.24 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
35
36
37
38
39
<?xml version="1.0"?>
<launch>
<arg name="odom_frame" default="odom"/>
<arg name="base_frame" default="base_footprint"/>
<arg name="global_frame" default="map"/>
<arg name="cmd_topic" default="cmd_vel" />
<arg name="odom_topic" default="odom" />
<arg name="laser_topic" default="scan" />
<arg name="config_dir" default="config" />
<arg name="wp_global_planner" default="false" doc="[true - wp_global_planner, false - global_planner]"/>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find wr8_software)/$(arg config_dir)/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find wr8_software)/$(arg config_dir)/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find wr8_software)/$(arg config_dir)/local_costmap_params.yaml" command="load" />
<rosparam file="$(find wr8_software)/$(arg config_dir)/global_costmap_params.yaml" command="load" />
<rosparam file="$(find wr8_software)/$(arg config_dir)/move_base_params.yaml" command="load" />
<rosparam file="$(find wr8_software)/$(arg config_dir)/wp_global_planner_params.yaml" command="load" if="$(arg wp_global_planner)"/>
<rosparam file="$(find wr8_software)/$(arg config_dir)/global_planner_params.yaml" command="load" unless="$(arg wp_global_planner)"/>
<rosparam file="$(find wr8_software)/$(arg config_dir)/teb_local_planner_params.yaml" command="load" />
<param name="global_costmap/global_frame" value="$(arg global_frame)"/>
<param name="global_costmap/robot_base_frame" value="$(arg base_frame)"/>
<param name="local_costmap/global_frame" value="$(arg global_frame)"/>
<param name="local_costmap/robot_base_frame" value="$(arg base_frame)"/>
<param name="base_global_planner" value="wp_global_planner/WPGlobalPlanner" if="$(arg wp_global_planner)"/>
<param name="base_global_planner" value="global_planner/GlobalPlanner" unless="$(arg wp_global_planner)"/>
<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS"/>
<remap from="cmd_vel" to="$(arg cmd_topic)"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg laser_topic)"/>
</node>
</launch>