Files
mir_amr/mir_robot/mir_navigation/launch/move_base.xml
2026-05-28 10:29:58 +07:00

30 lines
2.5 KiB
XML
Executable File

<launch>
<!--node ns="local_costmap" name="voxel_grid_throttle" pkg="topic_tools" type="throttle" args="messages voxel_grid 3.0 voxel_grid_throttled" /-->
<arg name="local_planner" default="dwb" doc="Local planner can be either dwa, base, teb or pose"/>
<arg name="with_virtual_walls" default="true" doc="Enables usage of virtual walls when set. Set to false when running SLAM." />
<arg name="with_preferred_zones" default="true" doc="Enables usage of preferred zones when set. Set to false when running SLAM." />
<arg name="with_unpreferred_zones" default="true" doc="Enables usage of unpreferred zones when set. Set to false when running SLAM." />
<arg name="with_critical_zones" default="true" doc="Enables usage of critical zones when set. Set to false when running SLAM." />
<arg name="with_direction_zones" default="false" doc="Enables usage of direction zones when set. Set to false when running SLAM." />
<arg name="prefix" default="" doc="Prefix used for robot tf frames" /> <!-- used in the config files -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base_node" output="screen" clear_params="true">
<param name="SBPLLatticePlanner/primitive_filename" value="$(find mir_navigation)/mprim/unicycle_highcost_5cm.mprim" />
<rosparam file="$(find mir_navigation)/config/move_base_common_params.yaml" command="load" />
<rosparam file="$(find mir_navigation)/config/sbpl_global_params.yaml" command="load" />
<rosparam file="$(find mir_navigation)/config/$(arg local_planner)_local_planner_params.yaml" command="load" />
<!-- global costmap params -->
<rosparam file="$(find mir_navigation)/config/costmap_common_params.yaml" command="load" ns="global_costmap" subst_value="true" />
<rosparam file="$(find mir_navigation)/config/costmap_global_params.yaml" command="load" />
<rosparam file="$(find mir_navigation)/config/costmap_global_params_plugins.yaml" command="load" />
<!-- local costmap params -->
<rosparam file="$(find mir_navigation)/config/costmap_common_params.yaml" command="load" ns="local_costmap" subst_value="true" />
<rosparam file="$(find mir_navigation)/config/costmap_local_params.yaml" command="load" subst_value="true" />
<rosparam file="$(find mir_navigation)/config/costmap_local_params_plugins.yaml" command="load" />
<remap from="map" to="/map" />
<remap from="marker" to="move_base_node/DWBLocalPlanner/markers" />
</node>
</launch>