XTDrone/motion_planning/2d/launch/move_base.launch

26 lines
1.6 KiB
XML

<launch>
<!-- Arguments -->
<arg name="motion_planning" default="/home/robin/Xtdrone/motion_planning/2d"/>
<arg name="cmd_vel_topic" default="/cmd_vel" />
<arg name="odom_topic" default="odom" />
<arg name="move_forward_only" default="false"/>
<!-- move_base -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_global_planner" value="global_planner/GlobalPlanner" />
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
<rosparam file="$(arg motion_planning)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(arg motion_planning)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(arg motion_planning)/param/local_costmap_params.yaml" command="load" />
<rosparam file="$(arg motion_planning)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(arg motion_planning)/param/move_base_params.yaml" command="load" />
<rosparam file="$(arg motion_planning)/param/dwa_local_planner_params.yaml" command="load" />
<rosparam file="$(arg motion_planning)/param/global_planner_params.yaml" command="load" />
<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
<remap from="odom" to="$(arg odom_topic)"/>
<param name="DWAPlannerROS/min_vel_x" value="0.0" if="$(arg move_forward_only)" />
<param name="DWAPlannerROS/max_vel_y" value="0.0" if="$(arg move_forward_only)" />
<param name="DWAPlannerROS/min_vel_y" value="0.0" if="$(arg move_forward_only)" />
</node>
</launch>