1 Star 0 Fork 9

allenqiu/robot_navigation

加入 Gitee
与超过 1200万 开发者一起发现、参与优秀开源项目,私有仓库也完全免费 :)
免费加入
文件
该仓库未声明开源许可证文件(LICENSE),使用请关注具体项目描述及其代码上游依赖。
克隆/下载
move_base.launch 3.84 KB
一键复制 编辑 原始数据 按行查看 历史
<launch>
<!-- Arguments -->
<arg name="cmd_vel_topic" default="cmd_vel" />
<arg name="odom_topic" default="odom" />
<arg name="planner" default="dwa" doc="opt: dwa, teb"/>
<arg name="simulation" default= "false"/>
<arg name="use_dijkstra" default= "true"/>
<arg name="base_type" default= "$(env BASE_TYPE)"/>
<arg name="move_forward_only" default="false"/>
<!-- move_base use DWA planner-->
<group if="$(eval planner == 'dwa')">
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<!-- use global_planner replace default navfn as global planner ,global_planner support A* and dijkstra algorithm-->
<param name="base_global_planner" value="global_planner/GlobalPlanner"/>
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
<!-- <rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/global_planner_params.yaml" command="load" /> -->
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/local_costmap_params.yaml" command="load" />
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/global_costmap_params.yaml" command="load" />
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/move_base_params.yaml" command="load" />
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/dwa_local_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)" />
<!--default is True,use dijkstra algorithm;set to False,usd A* algorithm-->
<param name="GlobalPlanner/use_dijkstra " value="$(arg use_dijkstra)" />
</node>
</group>
<!-- move_base use TEB planner-->
<group if="$(eval planner == 'teb')">
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<!-- use global_planner replace default navfn as global planner ,global_planner support A* and dijkstra algorithm-->
<param name="base_global_planner" value="global_planner/GlobalPlanner"/>
<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
<!-- <rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/global_planner_params.yaml" command="load" /> -->
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/local_costmap_params.yaml" command="load" />
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/global_costmap_params.yaml" command="load" />
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/move_base_params.yaml" command="load" />
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/teb_local_planner_params.yaml" command="load" />
<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
<remap from="odom" to="$(arg odom_topic)"/>
<param name="TebLocalPlannerROS/max_vel_x_backwards" value="0.0" if="$(arg move_forward_only)" />
<!--default is True,use dijkstra algorithm;set to False,usd A* algorithm-->
<param name="GlobalPlanner/use_dijkstra " value="$(arg use_dijkstra)" />
<!--stage simulator takes the angle instead of the rotvel as input (twist message)-->
</node>
</group>
<!-- move_base -->
</launch>
Loading...
马建仓 AI 助手
尝试更多
代码解读
代码找茬
代码优化
1
https://gitee.com/allenqiu2020/robot_navigation.git
git@gitee.com:allenqiu2020/robot_navigation.git
allenqiu2020
robot_navigation
robot_navigation
master

搜索帮助