|
@@ -15,8 +15,8 @@
|
|
|
<!-- startup EAI X2L lidar node -->
|
|
|
<include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
|
|
|
|
|
|
- <!-- startup move_base node -->
|
|
|
- <include file="$(find robot_navigation)/launch/move_base.launch" />
|
|
|
+ <!-- startup move_base node --><!-- 建图不需要启动move_base -->
|
|
|
+ <!-- <include file="$(find robot_navigation)/launch/move_base.launch" /> -->
|
|
|
|
|
|
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
|
|
|
<param name="odom_frame" value="odom_combined" />
|
|
@@ -48,7 +48,7 @@
|
|
|
<param name="ymin" value="-5.0"/>
|
|
|
<param name="xmax" value="5.0"/>
|
|
|
<param name="ymax" value="5.0"/>
|
|
|
- <param name="delta" value="0.02"/> <!--resolution of the map -->
|
|
|
+ <param name="delta" value="0.02"/> <!--resolution of the map --><!--大环境建图范围为0.05-0.1 -->
|
|
|
|
|
|
<param name="llsamplerange" value="0.01"/>
|
|
|
<param name="llsamplestep" value="0.01"/>
|