|
@@ -3,7 +3,9 @@
|
|
|
首先启动x2l雷达,然后启动gmapping节点.所有节点启动成功后,即可
|
|
|
开始gmapping建图,在rviz中可以查看整个建图过程.下面来解释一下
|
|
|
gmapping操作的重点参数:
|
|
|
- 1):delta:调节生成地图的分辨率,单位米.
|
|
|
+ 1):delta:调节生成地图的分辨率,每像素点代表实际的距离,单位米.
|
|
|
+ 2):map_update_interval:建立地图时每隔多长时间更新一下地图,单位秒,该值越小越消耗cpu资源.
|
|
|
+ 3):maxUrange:激光雷达使用的最大范围,超过该距离的雷达数据会舍弃不参与建图.
|
|
|
Author: corvin
|
|
|
History:
|
|
|
20200325:init this file.
|
|
@@ -15,18 +17,18 @@
|
|
|
<include file="$(find robot_navigation)/launch/ydlidar_X2L.launch" />
|
|
|
|
|
|
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
|
|
|
- <param name="odom_frame" value="odom_combined" />
|
|
|
-
|
|
|
- <param name="map_update_interval" value="5.0"/>
|
|
|
- <param name="maxUrange" value="7.5"/>
|
|
|
- <param name="sigma" value="0.05"/>
|
|
|
- <param name="kernelSize" value="1"/>
|
|
|
- <param name="lstep" value="0.05"/>
|
|
|
- <param name="astep" value="0.05"/>
|
|
|
- <param name="iterations" value="5"/>
|
|
|
- <param name="lsigma" value="0.075"/>
|
|
|
- <param name="ogain" value="3.0"/>
|
|
|
- <param name="lskip" value="0"/>
|
|
|
+ <param name="odom_frame" value="odom_combined"/>
|
|
|
+
|
|
|
+ <param name="map_update_interval" value="4.0"/>
|
|
|
+ <param name="maxUrange" value="7.0"/>
|
|
|
+ <param name="sigma" value="0.05"/>
|
|
|
+ <param name="kernelSize" value="1"/>
|
|
|
+ <param name="lstep" value="0.05"/>
|
|
|
+ <param name="astep" value="0.05"/>
|
|
|
+ <param name="iterations" value="5"/>
|
|
|
+ <param name="lsigma" value="0.075"/>
|
|
|
+ <param name="ogain" value="3.0"/>
|
|
|
+ <param name="lskip" value="0"/>
|
|
|
<param name="minimumScore" value="50"/>
|
|
|
|
|
|
<param name="srr" value="0.1"/>
|
|
@@ -38,18 +40,17 @@
|
|
|
<param name="angularUpdate" value="0.5"/>
|
|
|
<param name="temporalUpdate" value="3.0"/>
|
|
|
<param name="resampleThreshold" value="0.5"/>
|
|
|
- <param name="particles" value="30"/>
|
|
|
+ <param name="particles" value="30"/>
|
|
|
|
|
|
<param name="xmin" value="-5.0"/>
|
|
|
<param name="ymin" value="-5.0"/>
|
|
|
<param name="xmax" value="5.0"/>
|
|
|
<param name="ymax" value="5.0"/>
|
|
|
- <param name="delta" value="0.05"/> <!--resolution of the map --><!--大环境建图范围为0.05-0.1 -->
|
|
|
+ <param name="delta" value="0.05"/> <!--resolution of the map -->
|
|
|
|
|
|
<param name="llsamplerange" value="0.01"/>
|
|
|
<param name="llsamplestep" value="0.01"/>
|
|
|
<param name="lasamplerange" value="0.005"/>
|
|
|
<param name="lasamplestep" value="0.005"/>
|
|
|
</node>
|
|
|
-</launch>
|
|
|
-
|
|
|
+</launch>
|