• 欢迎访问开心洋葱网站,在线教程,推荐使用最新版火狐浏览器和Chrome浏览器访问本网站,欢迎加入开心洋葱 QQ群
  • 为方便开心洋葱网用户,开心洋葱官网已经开启复制功能!
  • 欢迎访问开心洋葱网站,手机也能访问哦~欢迎加入开心洋葱多维思维学习平台 QQ群
  • 如果您觉得本站非常有看点,那么赶紧使用Ctrl+D 收藏开心洋葱吧~~~~~~~~~~~~~!
  • 由于近期流量激增,小站的ECS没能经的起亲们的访问,本站依然没有盈利,如果各位看如果觉着文字不错,还请看官给小站打个赏~~~~~~~~~~~~~!

3.在STDR仿真器中使用gmapping构建2D栅格地图

人工智能 ROS小课堂 1870次浏览 0个评论

0x00 gmapping简介

gmapping是一种高效的Rao-Blackwellized粒子滤波器,用于根据激光雷达测距数据来生成2D珊格地图。gmapping是OpenSLAM下的GMapping在ROS下的一个再封装移植版本,在ROS下完成SLAM的整个过程中,使用gmapping进行构建地图是第一步也是非常重要的一步,因为完整精确的地图是机器人进行定位和路径规划、自动导航和避障的重要前提条件。


0x01 创建stdr_gmapping软件包

开始创建stdr_gmapping软件包,该软件包我们通过调用ros系统提供的gmapping软件包下slam_gmapping节点来完成gmapping建图,因此第一件事就是保证当前ROS系统下已经安装好gmapping软件包,通过以下命令来安装:

sudo apt-get install ros-$ROS_DISTRO-gmapping

接下来在catkin_ws的src目录下来创建stdr_gmapping软件包,操作步骤如下图所示:

3.在STDR仿真器中使用gmapping构建2D栅格地图

下面开始编写launch文件stdr_gmapping.launch,代码如下:

<!--
  Copyright(c): 2016-2018 ROS小课堂 www.corvin.cn
  Author: corvin
  Description:
    使用stdr的仿真robot下的laser来进行gmapping构图,在这里使用的是/robot0/laser_0。
  History:
    20180523: initial this file.
-->
<launch>
  <arg name="base_frame" default="robot0" />
  <arg name="map_frame" default="map" />
  <arg name="odom_frame" default="odom" />
  <!-- startup stdr simulator with robot0 -->
  <include file="$(find stdr_launchers)/launch/server_with_map_and_gui_plus_robot.launch" />
  <!-- startup rviz to show gmapping process -->
  <node name="rviz" type="rviz" pkg="rviz" args="-d $(find stdr_gmapping)/rviz/stdr_gmapping_config.rviz" />
  <!-- startup slam_gmapping node -->
  <node pkg="gmapping" type="slam_gmapping" name="stdr_gmapping_node" output="screen">
      <remap from="scan" to="/robot0/laser_0" />
      <remap from="map"  to="/gmapping/map" />
      <param name="throttle_scans" value="1" />
      <param name="base_frame" value="$(arg base_frame)"/>
      <param name="map_frame" value="$(arg map_frame)"/>
      <param name="odom_frame" value="$(arg odom_frame)"/>
      <param name="map_update_interval" value="3.0"/>
      <!-- set maxUrange < maximum range of the real sensor <= maxRange -->
      <param name="maxUrange" value="3.9"/>
      <param name="maxRange"  value="4.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="80"/>
      <param name="srr" value="0.1"/>
      <param name="srt" value="0.2"/>
      <param name="str" value="0.1"/>
      <param name="stt" value="0.2"/>
      <param name="linearUpdate" value="1.0"/>
      <param name="angularUpdate" value="0.5"/>
      <param name="temporalUpdate" value="4.0"/>
      <param name="resampleThreshold" value="0.5"/>
      <param name="particles" value="30"/>
      <param name="xmin"  value="-7.0" />
      <param name="ymin"  value="-7.0" />
      <param name="xmax"  value="7.0" />
      <param name="ymax"  value="7.0" />
      <param name="delta" value="0.05" />
      <param name="llsamplerange" value="0.01" />
      <param name="llsamplestep"  value="0.01" />
      <param name="lasamplerange" value="0.005" />
      <param name="lasamplestep"  value="0.005" />
      <param name="transform_publish_period"  value="0.05" />
      <param name="occ_thresh" value="0.25" />
  </node>
</launch>

由于在该launch文件中要加载rviz配置文件来显示整个建图过程,因此下面提供rviz配置文件内容,但是由于该文件内容较长因此提供下载链接stdr_gmapping_config.rviz.tar.gz,将其解压后放在rviz目录下即可。

3.在STDR仿真器中使用gmapping构建2D栅格地图


0x02 启动stdr_gmapping开始建图

当代码准备好以后可以开始来使用slam_gmapping建图了,在调用命令之前需要先source devel/setup.bash配置环境变量,然后执行如下命令:

roslaunch stdr_gmapping stdr_gmapping_keyboard.launch

3.在STDR仿真器中使用gmapping构建2D栅格地图

接下来就可以来使用键盘遥控小车移动软件包teleop_twist_keyboard来控制仿真小车四处走动来建地图了,需要注意的是该软件包默认是向/cmd_vel话题发送控制指令,可以使用如下命令来向/robot0/cmd_vel话题发送控制指令遥控stdr中仿真小车的移动:

rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=robot0/cmd_vel

除去上述方法还可以直接修改teleop_twist_keyboard软件包下的teleop_twist_keyboard.py源码文件,将其中的控制移动话题修改:

3.在STDR仿真器中使用gmapping构建2D栅格地图

当开始使用键盘遥控仿真小车四处走动时,就可以发现地图在不断的创建中:

3.在STDR仿真器中使用gmapping构建2D栅格地图

在进行gmapping过程中的节点和话题关系图如下,方便我们了解认识整个过程:

3.在STDR仿真器中使用gmapping构建2D栅格地图


0x03 保存构建好的完整地图

当使用键盘遥控仿真小车将地图走过一遍那么地图也就建立好了,我们需要保存当前地图为了将来的自动导航使用,完整地图如下所示:

3.在STDR仿真器中使用gmapping构建2D栅格地图

我们需要使用map_server软件包里的map_saver来保存当前的地图,首先需要保证已经安装了map_server软件包,安装命令如下:

sudo apt-get install ros-$ROS_DISTRO-map-server

当安装好map_server后,接下来就可以使用如下命令来保存地图了,在stdr_gmapping的maps目录下执行命令如下:

rosrun map_server map_saver map:=/gmapping/map -f mymap

3.在STDR仿真器中使用gmapping构建2D栅格地图

为了方便后面快速的保存地图,不用输入这么长的命令,我们可以编写一个脚本saveMap.sh,具体如下图所示:

3.在STDR仿真器中使用gmapping构建2D栅格地图


0x04 gmapping中各参数意义讲解

下面来分析下stdr_gmapping.launch中各参数的意义,下面来分成一段一段的来介绍:

3.在STDR仿真器中使用gmapping构建2D栅格地图

(1)设置base_frame为robot0是因为在stdr仿真环境中默认设置的机器人底盘tf是robot0,一般在真实的机器人上设置为base_link或者base_footprint,仿真环境的tf树如下图所示:

3.在STDR仿真器中使用gmapping构建2D栅格地图

(2)重新映射scan话题为/robot0/laser_0是因为仿真机器人的激光雷达输出话题为/robot0/laser_0,因为默认的gmapping需要订阅的是scan话题,所以我们需要做重映射。

(3)重映射map为/gmapping/map是因为在stdr仿真环境中,已经将/map话题作为下面这张地图的输出话题了,所以我们需要将gmapping默认输出的/map话题重新映射为/gmapping/map,否则gmapping输出的默认话题/map会影响stdr的静态地图正常工作的,会导致stdr可能crash。

3.在STDR仿真器中使用gmapping构建2D栅格地图

3.在STDR仿真器中使用gmapping构建2D栅格地图

接下来开始分析launch文件下面一段参数,如下图所示:

3.在STDR仿真器中使用gmapping构建2D栅格地图

(1)map_update_interval:是gmapping过程中每个几秒更新一次地图,该值变小的话表明更新地图的频率加快,会增加消耗更多当前系统的CPU计算资源。同时地图更新也受scanmach的影响,如果scanmatch没有成功的话,不会更新地图。

(2)maxUrange是雷达可用的最大有效测距值,maxRange是雷达的理论最大测距值,一般情况下设置maxUrange < 雷达的现实实际测距值 <= maxRange。

(3)下面这些参数一般不用修改保持默认值即可:

sigma (float, default: 0.05),endpoint匹配标准差

kernelSize (int, default: 1),用于查找对应的kernel size

lstep (float, default: 0.05),平移优化步长

astep (float, default: 0.05),旋转优化步长

iterations (int, default: 5),扫描匹配迭代步数

lsigma (float, default: 0.075),用于扫描匹配概率的激光标准差

ogain (float, default: 3.0),似然估计为平滑重采样影响使用的gain

lskip (int, default: 0),每次扫描跳过的光束数.

(4)minimumScore: 最小匹配得分,这个参数很重要,它决定了对激光的一个置信度,越高说明对激光匹配算法的要求越高,激光的匹配也越容易失败而转去使用里程计数据,而设的太低又会使地图中出现大量噪声,所以需要权衡调整。

3.在STDR仿真器中使用gmapping构建2D栅格地图

(1)srr,srt,str,stt四个参数是运动模型的噪声参数,一般设置为默认值不用修改。

(2)linearUpdate:机器人移动多远距离,进行一次scanmatch匹配。

         angularUpdate:机器人旋转多少弧度,进行一次scanmatch匹配。

(3)temporalUpdate:如果最新扫描处理比更新慢,则处理1次扫描,该值为负数时候关闭基于时间的更新,该参数很重要,需要重点关注。

(4)resampleThreshold:基于重采样门限的Neff

(5)particles:gmapping算法中的粒子数,因为gmapping使用的是粒子滤波算法,粒子在不断地迭代更新,所以选取一个合适的粒子数可以让算法在保证比较准确的同时有较高的速度。

3.在STDR仿真器中使用gmapping构建2D栅格地图

(1)xmin,ymin,xmax,ymax:初始化的地图大小。

(2)delta:创建的地图分辨率,默认是0.05m。

(3)llsamplerange:线速度移动多长距离进行似然估计。

         llsamplestep:线速度移动多少步长进行似然估计。

(4)lasamplerange:每转动多少弧度用于似然估计。

         lasamplestep:用于似然估计的弧度采样步长是多少。

(5)transform_publish_period:多长时间发布一次tf转换(map->odom转换),单位是秒。

(6)occ_thresh:在gmapping过程中占有栅格地图的阈值,只有当前单元格的占有率超过该值才认为是被占有。如果设置该值为1的话就会导致任何障碍物都不会认为是占有。

现在大家已经对gmapping中各参数有了初步认识,现在大家可以来自己动手修改各参数,然后重新启动gmapping的仿真来看修改的参数对建图的影响,这样才会对各参数的意义理解的更为深刻,谨记谨记!


0x05 使用gmapping软件包注意事项

通过上面的实验已经对使用gmapping来建图有个初步认识了,那接下来就来仔细介绍下gmapping这个软件包正常运行的一些依赖条件和运行后的输出是什么:

3.在STDR仿真器中使用gmapping构建2D栅格地图


0x06 参考资料

[1].ROS WiKi上gmapping的主页[OL]. http://wiki.ros.org/gmapping

[2].slam_gampping配置文件参数介绍[OL]. https://www.ncnynl.com/archives/201702/1364.html

[3].键盘遥控移动软件包teleop_twist_keyboard在ROS wiki上主页[OL]. http://wiki.ros.org/teleop_twist_keyboard


0x07 问题反馈

大家在按照教程操作过程中有任何问题,可以关注ROS小课堂的官方微信公众号,在公众号中给我发消息反馈问题即可,我基本上每天都会处理公众号中的留言!当然如果你要是顺便给ROS小课堂打个赏,我也会感激不尽的,打赏30块还会邀请进ROS小课堂的微信群与更多志同道合的小伙伴一起学习和交流!


开心洋葱 , 版权所有丨如未注明 , 均为原创丨未经授权请勿修改 , 转载请注明3.在STDR仿真器中使用gmapping构建2D栅格地图
喜欢 (0)

您必须 登录 才能发表评论!

加载中……