代码拉取完成,页面将自动刷新
同步操作将从 冰达机器人/robot_navigation 强制同步,此操作会覆盖自 Fork 仓库以来所做的任何修改,且无法恢复!!!
确定后同步将在后台操作,完成时将刷新页面,请耐心等待。
<launch>
<!-- Arguments -->
<arg name="map_file" default="$(find robot_navigation)/maps/map.yaml"/>
<arg name="simulation" default= "false"/>
<arg name="planner" default="dwa" doc="opt: dwa, teb"/>
<arg name="move_forward_only" default="false"/>
<arg name="use_dijkstra" default= "true"/>
<!-- Map server -->
<node pkg="map_server" name="map_server" type="map_server" args="$(arg map_file)">
<param name="frame_id" value="map"/>
</node>
<!-- AMCL -->
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<rosparam file="$(find robot_navigation)/param/$(env BASE_TYPE)/amcl_params.yaml" command="load" />
<param name="initial_pose_x" value="0.0"/>
<param name="initial_pose_y" value="0.0"/>
<param name="initial_pose_a" value="0.0"/>
</node>
<!-- move_base -->
<include file="$(find robot_navigation)/launch/move_base.launch" >
<arg name="planner" value="$(arg planner)"/>
<arg name="simulation" value="$(arg simulation)"/>
<arg name="move_forward_only" value="$(arg move_forward_only)"/>
<arg name="use_dijkstra" value="$(arg use_dijkstra)"/>
</include>
</launch>
此处可能存在不合适展示的内容,页面不予展示。您可通过相关编辑功能自查并修改。
如您确认内容无涉及 不当用语 / 纯广告导流 / 暴力 / 低俗色情 / 侵权 / 盗版 / 虚假 / 无价值内容或违法国家有关法律法规的内容,可点击提交进行申诉,我们将尽快为您处理。