|
@@ -3,14 +3,15 @@
|
|
|
首先启动x2l雷达,然后启动gmapping节点.所有节点启动成功后,即可
|
|
|
开始gmapping建图,在rviz中可以查看整个建图过程.下面来解释一下
|
|
|
gmapping操作的重点参数:
|
|
|
- 1):delta:调节生成地图的分辨率,每像素点代表实际的距离,单位米.
|
|
|
- 2):map_update_interval:建立地图时每隔多长时间更新一下地图,单位秒,该值越小越消耗cpu资源.
|
|
|
- 3):maxUrange:激光雷达使用的最大范围,超过该距离的雷达数据会舍弃不参与建图.
|
|
|
+ 1)delta:调节生成地图的分辨率,每像素点代表实际的距离,单位米.
|
|
|
+ 2)map_update_interval:建立地图时每隔多长时间更新一下地图,单位秒,该值越小越消耗cpu资源.
|
|
|
+ 3)maxUrange:激光雷达使用的最大范围,超过该距离的雷达数据会舍弃不参与建图.
|
|
|
Author: corvin
|
|
|
History:
|
|
|
20200325:init this file.
|
|
|
20220902:增加启动gmapping建图前先把robot_bringup.launch加载启动,
|
|
|
然后加载gmapping算法开始建地图,最后加载view_navigation.launch查看建图过程;
|
|
|
+ 20201005:将gmapping建图过程在依赖的odom_frame从odom_combined更新为odom;
|
|
|
-->
|
|
|
<launch>
|
|
|
<param name="use_sim_time" value="false"/>
|
|
@@ -22,7 +23,7 @@
|
|
|
<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="odom_frame" value="odom"/>
|
|
|
|
|
|
<param name="map_update_interval" value="4.0"/>
|
|
|
<param name="maxUrange" value="7.0"/>
|
|
@@ -61,4 +62,4 @@
|
|
|
|
|
|
<!-- startup view_navigation.launch -->
|
|
|
<include file="$(find robot_navigation)/launch/view_navigation.launch"/>
|
|
|
-</launch>
|
|
|
+</launch>
|