|
@@ -12,6 +12,8 @@
|
|
|
20220902:增加启动gmapping建图前先把robot_bringup.launch加载启动,
|
|
|
然后加载gmapping算法开始建地图,最后加载view_navigation.launch查看建图过程;
|
|
|
20201005:将gmapping建图过程在依赖的odom_frame从odom_combined更新为odom;
|
|
|
+ 20201019:更新map_update_interval参数从4->3,3秒更新一次地图,建立的地图大小
|
|
|
+ xmin,xmax,ymin,ymax更新为6;
|
|
|
-->
|
|
|
<launch>
|
|
|
<param name="use_sim_time" value="false"/>
|
|
@@ -25,7 +27,7 @@
|
|
|
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
|
|
|
<param name="odom_frame" value="odom"/>
|
|
|
|
|
|
- <param name="map_update_interval" value="4.0"/>
|
|
|
+ <param name="map_update_interval" value="3.0"/>
|
|
|
<param name="maxUrange" value="7.0"/>
|
|
|
<param name="sigma" value="0.05"/>
|
|
|
<param name="kernelSize" value="1"/>
|
|
@@ -48,10 +50,10 @@
|
|
|
<param name="resampleThreshold" value="0.5"/>
|
|
|
<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="xmin" value="-6.0"/>
|
|
|
+ <param name="ymin" value="-6.0"/>
|
|
|
+ <param name="xmax" value="6.0"/>
|
|
|
+ <param name="ymax" value="6.0"/>
|
|
|
<param name="delta" value="0.05"/> <!--resolution of the map -->
|
|
|
|
|
|
<param name="llsamplerange" value="0.01"/>
|